#include <outofcore_cloud.h>

Classes | |
| class | CloudDataCacheItem |
| struct | PcdQueueItem |
Public Types | |
| typedef LRUCache< std::string, CloudDataCacheItem > | CloudDataCache |
| typedef std::priority_queue < PcdQueueItem > | PcdQueue |
Public Member Functions | |
| void | decreaseLodPixelThreshold () |
| Eigen::Vector3d | getBoundingBoxMax () |
| Eigen::Vector3d | getBoundingBoxMin () |
| vtkSmartPointer < vtkActorCollection > | getCloudActors () const |
| uint64_t | getDataLoaded () |
| int | getDisplayDepth () |
| bool | getDisplayVoxels () |
| int | getLodPixelThreshold () |
| OctreeDiskPtr | getOctree () |
| uint64_t | getPointsLoaded () |
| vtkSmartPointer< vtkActor > | getVoxelActor () const |
| void | increaseLodPixelThreshold () |
| OutofcoreCloud (std::string name, boost::filesystem::path &tree_root) | |
| virtual void | render (vtkRenderer *renderer) |
| void | setDisplayDepth (int displayDepth) |
| void | setDisplayVoxels (bool display_voxels) |
| void | setLodPixelThreshold (int lod_pixel_threshold) |
| void | setRenderCamera (Camera *render_camera) |
| void | updateVoxelData () |
Static Public Member Functions | |
| static void | pcdReaderThread () |
Static Public Attributes | |
| static CloudDataCache | cloud_data_cache |
| static boost::mutex | cloud_data_cache_mutex |
| static PcdQueue | pcd_queue |
| static boost::mutex | pcd_queue_mutex |
| static boost::condition | pcd_queue_ready |
| static boost::shared_ptr < boost::thread > | pcd_reader_thread |
Private Types | |
| typedef Eigen::aligned_allocator < PointT > | AlignedPointT |
| typedef std::map< std::string, vtkSmartPointer< vtkActor > > | CloudActorMap |
| typedef pcl::outofcore::OutofcoreOctreeBase | OctreeDisk |
| typedef pcl::outofcore::OutofcoreOctreeBaseNode | OctreeDiskNode |
| typedef boost::shared_ptr < OctreeDisk > | OctreeDiskPtr |
| typedef pcl::PointXYZ | PointT |
Private Attributes | |
| Eigen::Vector3d | bbox_max_ |
| Eigen::Vector3d | bbox_min_ |
| vtkSmartPointer < vtkActorCollection > | cloud_actors_ |
| std::map< std::string, vtkSmartPointer< vtkActor > > | cloud_actors_map_ |
| uint64_t | data_loaded_ |
| uint64_t | display_depth_ |
| int | lod_pixel_threshold_ |
| OctreeDiskPtr | octree_ |
| uint64_t | points_loaded_ |
| Camera * | render_camera_ |
| vtkSmartPointer< vtkActor > | voxel_actor_ |
Definition at line 35 of file outofcore_cloud.h.
typedef Eigen::aligned_allocator<PointT> OutofcoreCloud::AlignedPointT [private] |
Definition at line 48 of file outofcore_cloud.h.
typedef std::map<std::string, vtkSmartPointer<vtkActor> > OutofcoreCloud::CloudActorMap [private] |
Definition at line 52 of file outofcore_cloud.h.
Definition at line 114 of file outofcore_cloud.h.
typedef pcl::outofcore::OutofcoreOctreeBase OutofcoreCloud::OctreeDisk [private] |
Definition at line 43 of file outofcore_cloud.h.
typedef pcl::outofcore::OutofcoreOctreeBaseNode OutofcoreCloud::OctreeDiskNode [private] |
Definition at line 44 of file outofcore_cloud.h.
typedef boost::shared_ptr<OctreeDisk> OutofcoreCloud::OctreeDiskPtr [private] |
Definition at line 47 of file outofcore_cloud.h.
| typedef std::priority_queue<PcdQueueItem> OutofcoreCloud::PcdQueue |
Definition at line 84 of file outofcore_cloud.h.
typedef pcl::PointXYZ OutofcoreCloud::PointT [private] |
Definition at line 39 of file outofcore_cloud.h.
| OutofcoreCloud::OutofcoreCloud | ( | std::string | name, |
| boost::filesystem::path & | tree_root | ||
| ) |
Definition at line 116 of file outofcore_cloud.cpp.
| void OutofcoreCloud::decreaseLodPixelThreshold | ( | ) | [inline] |
Definition at line 249 of file outofcore_cloud.h.
| Eigen::Vector3d OutofcoreCloud::getBoundingBoxMax | ( | ) | [inline] |
Definition at line 194 of file outofcore_cloud.h.
| Eigen::Vector3d OutofcoreCloud::getBoundingBoxMin | ( | ) | [inline] |
Definition at line 188 of file outofcore_cloud.h.
| vtkSmartPointer<vtkActorCollection> OutofcoreCloud::getCloudActors | ( | ) | const [inline] |
Definition at line 144 of file outofcore_cloud.h.
| uint64_t OutofcoreCloud::getDataLoaded | ( | ) | [inline] |
Definition at line 182 of file outofcore_cloud.h.
| int OutofcoreCloud::getDisplayDepth | ( | ) | [inline] |
Definition at line 170 of file outofcore_cloud.h.
| bool OutofcoreCloud::getDisplayVoxels | ( | ) | [inline] |
Definition at line 206 of file outofcore_cloud.h.
| int OutofcoreCloud::getLodPixelThreshold | ( | ) | [inline] |
Definition at line 218 of file outofcore_cloud.h.
| OctreeDiskPtr OutofcoreCloud::getOctree | ( | ) | [inline] |
Definition at line 132 of file outofcore_cloud.h.
| uint64_t OutofcoreCloud::getPointsLoaded | ( | ) | [inline] |
Definition at line 176 of file outofcore_cloud.h.
| vtkSmartPointer<vtkActor> OutofcoreCloud::getVoxelActor | ( | ) | const [inline] |
Definition at line 138 of file outofcore_cloud.h.
| void OutofcoreCloud::increaseLodPixelThreshold | ( | ) | [inline] |
Definition at line 233 of file outofcore_cloud.h.
| void OutofcoreCloud::pcdReaderThread | ( | ) | [static] |
Definition at line 52 of file outofcore_cloud.cpp.
| void OutofcoreCloud::render | ( | vtkRenderer * | renderer | ) | [virtual] |
Reimplemented from Object.
Definition at line 174 of file outofcore_cloud.cpp.
| void OutofcoreCloud::setDisplayDepth | ( | int | displayDepth | ) | [inline] |
Definition at line 150 of file outofcore_cloud.h.
| void OutofcoreCloud::setDisplayVoxels | ( | bool | display_voxels | ) | [inline] |
Definition at line 200 of file outofcore_cloud.h.
| void OutofcoreCloud::setLodPixelThreshold | ( | int | lod_pixel_threshold | ) | [inline] |
Definition at line 224 of file outofcore_cloud.h.
| void OutofcoreCloud::setRenderCamera | ( | Camera * | render_camera | ) | [inline] |
Definition at line 212 of file outofcore_cloud.h.
| void OutofcoreCloud::updateVoxelData | ( | ) |
Definition at line 143 of file outofcore_cloud.cpp.
Eigen::Vector3d OutofcoreCloud::bbox_max_ [private] |
Definition at line 279 of file outofcore_cloud.h.
Eigen::Vector3d OutofcoreCloud::bbox_min_ [private] |
Definition at line 279 of file outofcore_cloud.h.
vtkSmartPointer<vtkActorCollection> OutofcoreCloud::cloud_actors_ [private] |
Definition at line 288 of file outofcore_cloud.h.
std::map<std::string, vtkSmartPointer<vtkActor> > OutofcoreCloud::cloud_actors_map_ [private] |
Definition at line 287 of file outofcore_cloud.h.
Definition at line 115 of file outofcore_cloud.h.
boost::mutex OutofcoreCloud::cloud_data_cache_mutex [static] |
Definition at line 116 of file outofcore_cloud.h.
uint64_t OutofcoreCloud::data_loaded_ [private] |
Definition at line 277 of file outofcore_cloud.h.
uint64_t OutofcoreCloud::display_depth_ [private] |
Definition at line 275 of file outofcore_cloud.h.
int OutofcoreCloud::lod_pixel_threshold_ [private] |
Definition at line 283 of file outofcore_cloud.h.
OctreeDiskPtr OutofcoreCloud::octree_ [private] |
Definition at line 273 of file outofcore_cloud.h.
Definition at line 85 of file outofcore_cloud.h.
boost::mutex OutofcoreCloud::pcd_queue_mutex [static] |
Definition at line 86 of file outofcore_cloud.h.
boost::condition OutofcoreCloud::pcd_queue_ready [static] |
Definition at line 87 of file outofcore_cloud.h.
boost::shared_ptr< boost::thread > OutofcoreCloud::pcd_reader_thread [static] |
Definition at line 60 of file outofcore_cloud.h.
uint64_t OutofcoreCloud::points_loaded_ [private] |
Definition at line 276 of file outofcore_cloud.h.
Camera* OutofcoreCloud::render_camera_ [private] |
Definition at line 281 of file outofcore_cloud.h.
vtkSmartPointer<vtkActor> OutofcoreCloud::voxel_actor_ [private] |
Definition at line 285 of file outofcore_cloud.h.