outofcore_cloud.h
Go to the documentation of this file.
00001 #ifndef PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_
00002 #define PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_
00003 
00004 // PCL
00005 //#include <pcl/common/time.h>
00006 //#include <pcl/point_cloud.h>
00007 #include <pcl/point_types.h>
00008 
00009 // PCL - outofcore
00010 #include <pcl/outofcore/outofcore.h>
00011 #include <pcl/outofcore/outofcore_impl.h>
00012 //#include <pcl/outofcore/impl/monitor_queue.hpp>
00013 #include <pcl/outofcore/impl/lru_cache.hpp>
00014 
00015 // PCL
00016 #include "camera.h"
00017 //#include <pcl/outofcore/visualization/object.h>
00018 
00019 // VTK
00020 #include <vtkActor.h>
00021 #include <vtkActorCollection.h>
00022 #include <vtkAppendPolyData.h>
00023 #include <vtkDataSetMapper.h>
00024 //#include <vtkCamera.h>
00025 //#include <vtkCameraActor.h>
00026 //#include <vtkHull.h>
00027 //#include <vtkPlanes.h>
00028 #include <vtkPolyData.h>
00029 //#include <vtkPolyDataMapper.h>
00030 //#include <vtkProperty.h>
00031 #include <vtkSmartPointer.h>
00032 
00033 //class Camera;
00034 
00035 class OutofcoreCloud : public Object
00036 {
00037     // Typedefs
00038     // -----------------------------------------------------------------------------
00039     typedef pcl::PointXYZ PointT;
00040 //    typedef pcl::outofcore::OutofcoreOctreeBase<pcl::outofcore::OutofcoreOctreeDiskContainer<PointT>, PointT> octree_disk;
00041 //    typedef pcl::outofcore::OutofcoreOctreeBaseNode<pcl::outofcore::OutofcoreOctreeDiskContainer<PointT>, PointT> octree_disk_node;
00042 
00043     typedef pcl::outofcore::OutofcoreOctreeBase<> OctreeDisk;
00044     typedef pcl::outofcore::OutofcoreOctreeBaseNode<> OctreeDiskNode;
00045 //    typedef pcl::outofcore::OutofcoreBreadthFirstIterator<> OctreeBreadthFirstIterator;
00046 
00047     typedef boost::shared_ptr<OctreeDisk> OctreeDiskPtr;
00048     typedef Eigen::aligned_allocator<PointT> AlignedPointT;
00049 
00050 
00051 
00052     typedef std::map<std::string, vtkSmartPointer<vtkActor> > CloudActorMap;
00053 
00054   public:
00055 
00056 //    typedef std::map<std::string, vtkSmartPointer<vtkPolyData> > CloudDataCache;
00057 //    typedef std::map<std::string, vtkSmartPointer<vtkPolyData> >::iterator CloudDataCacheIterator;
00058 
00059 
00060     static boost::shared_ptr<boost::thread> pcd_reader_thread;
00061     //static MonitorQueue<std::string> pcd_queue;
00062 
00063     struct PcdQueueItem
00064     {
00065       PcdQueueItem (std::string pcd_file, float coverage)
00066       {
00067        this->pcd_file = pcd_file;
00068        this->coverage = coverage;
00069       }
00070 
00071       bool operator< (const PcdQueueItem& rhs) const
00072       {
00073        if (coverage < rhs.coverage)
00074        {
00075          return true;
00076        }
00077        return false;
00078       }
00079 
00080       std::string pcd_file;
00081       float coverage;
00082     };
00083 
00084     typedef std::priority_queue<PcdQueueItem> PcdQueue;
00085     static PcdQueue pcd_queue;
00086     static boost::mutex pcd_queue_mutex;
00087     static boost::condition pcd_queue_ready;
00088 
00089     class CloudDataCacheItem : public LRUCacheItem< vtkSmartPointer<vtkPolyData> >
00090     {
00091     public:
00092 
00093       CloudDataCacheItem (std::string pcd_file, float coverage, vtkSmartPointer<vtkPolyData> cloud_data, size_t timestamp)
00094       {
00095        this->pcd_file = pcd_file;
00096        this->coverage = coverage;
00097        this->item = cloud_data;
00098        this->timestamp = timestamp;
00099       }
00100 
00101       virtual size_t
00102       sizeOf() const
00103       {
00104         return item->GetActualMemorySize();
00105       }
00106 
00107       std::string pcd_file;
00108       float coverage;
00109     };
00110 
00111 
00112 //    static CloudDataCache cloud_data_map;
00113 //    static boost::mutex cloud_data_map_mutex;
00114     typedef LRUCache<std::string, CloudDataCacheItem> CloudDataCache;
00115     static CloudDataCache cloud_data_cache;
00116     static boost::mutex cloud_data_cache_mutex;
00117 
00118     static void pcdReaderThread();
00119 
00120     // Operators
00121     // -----------------------------------------------------------------------------
00122     OutofcoreCloud (std::string name, boost::filesystem::path& tree_root);
00123 
00124     // Methods
00125     // -----------------------------------------------------------------------------
00126     void
00127     updateVoxelData ();
00128 
00129     // Accessors
00130     // -----------------------------------------------------------------------------
00131     OctreeDiskPtr
00132     getOctree ()
00133     {
00134       return octree_;
00135     }
00136 
00137     inline vtkSmartPointer<vtkActor>
00138     getVoxelActor () const
00139     {
00140       return voxel_actor_;
00141     }
00142 
00143     inline vtkSmartPointer<vtkActorCollection>
00144     getCloudActors () const
00145     {
00146       return cloud_actors_;
00147     }
00148 
00149     void
00150     setDisplayDepth (int displayDepth)
00151     {
00152       if (displayDepth < 0)
00153       {
00154         displayDepth = 0;
00155       }
00156       else if (displayDepth > octree_->getDepth ())
00157       {
00158         displayDepth = octree_->getDepth ();
00159       }
00160 
00161       if (display_depth_ != displayDepth)
00162       {
00163         display_depth_ = displayDepth;
00164         updateVoxelData ();
00165         //updateCloudData();
00166       }
00167     }
00168 
00169     int
00170     getDisplayDepth ()
00171     {
00172       return display_depth_;
00173     }
00174 
00175     uint64_t
00176     getPointsLoaded ()
00177     {
00178       return points_loaded_;
00179     }
00180 
00181     uint64_t
00182     getDataLoaded ()
00183     {
00184       return data_loaded_;
00185     }
00186 
00187     Eigen::Vector3d
00188     getBoundingBoxMin ()
00189     {
00190       return bbox_min_;
00191     }
00192 
00193     Eigen::Vector3d
00194     getBoundingBoxMax ()
00195     {
00196       return bbox_max_;
00197     }
00198 
00199     void
00200     setDisplayVoxels (bool display_voxels)
00201     {
00202       voxel_actor_->SetVisibility (display_voxels);
00203     }
00204 
00205     bool
00206     getDisplayVoxels()
00207     {
00208       return voxel_actor_->GetVisibility ();
00209     }
00210 
00211     void
00212     setRenderCamera(Camera *render_camera)
00213     {
00214       render_camera_ = render_camera;
00215     }
00216 
00217     int
00218     getLodPixelThreshold ()
00219     {
00220       return lod_pixel_threshold_;
00221     }
00222 
00223     void
00224     setLodPixelThreshold (int lod_pixel_threshold)
00225     {
00226       if (lod_pixel_threshold <= 1000)
00227         lod_pixel_threshold = 1000;
00228 
00229       lod_pixel_threshold_ = lod_pixel_threshold;
00230     }
00231 
00232     void
00233     increaseLodPixelThreshold ()
00234     {
00235       int value = 1000;
00236 
00237       if (lod_pixel_threshold_ >= 50000)
00238         value = 10000;
00239       if (lod_pixel_threshold_ >= 10000)
00240         value = 5000;
00241       else if (lod_pixel_threshold_ >= 1000)
00242         value = 100;
00243 
00244       lod_pixel_threshold_ += value;
00245       std::cout << "Increasing lod pixel threshold: " << lod_pixel_threshold_ << endl;
00246     }
00247 
00248     void
00249     decreaseLodPixelThreshold ()
00250     {
00251       int value = 1000;
00252       if (lod_pixel_threshold_ > 50000)
00253         value = 10000;
00254       else if (lod_pixel_threshold_ > 10000)
00255         value = 5000;
00256       else if (lod_pixel_threshold_ > 1000)
00257         value = 100;
00258 
00259       lod_pixel_threshold_ -= value;
00260 
00261       if (lod_pixel_threshold_ < 100)
00262         lod_pixel_threshold_ = 100;
00263       std::cout << "Decreasing lod pixel threshold: " << lod_pixel_threshold_ << endl;
00264     }
00265 
00266     virtual void
00267     render (vtkRenderer* renderer);
00268 
00269   private:
00270 
00271     // Members
00272     // -----------------------------------------------------------------------------
00273     OctreeDiskPtr octree_;
00274 
00275     uint64_t display_depth_;
00276     uint64_t points_loaded_;
00277     uint64_t data_loaded_;
00278 
00279     Eigen::Vector3d bbox_min_, bbox_max_;
00280 
00281     Camera *render_camera_;
00282 
00283     int lod_pixel_threshold_;
00284 
00285     vtkSmartPointer<vtkActor> voxel_actor_;
00286 
00287     std::map<std::string, vtkSmartPointer<vtkActor> > cloud_actors_map_;
00288     vtkSmartPointer<vtkActorCollection> cloud_actors_;
00289 
00290   public:
00291     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00292 };
00293 
00294 #endif


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