#include <iostream>
#include <string>
#include <pcl/common/time.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/io/pcd_io.h>
#include <pcl/io/vtk_lib_io.h>
#include <pcl/pcl_macros.h>
#include <pcl/console/print.h>
#include <pcl/console/parse.h>
#include <pcl/visualization/common/common.h>
#include <pcl/visualization/vtk/vtkVertexBufferObjectMapper.h>
#include <pcl/outofcore/outofcore.h>
#include <pcl/outofcore/outofcore_impl.h>
#include <pcl/outofcore/visualization/axes.h>
#include <pcl/outofcore/visualization/camera.h>
#include <pcl/outofcore/visualization/grid.h>
#include <pcl/outofcore/visualization/object.h>
#include <pcl/outofcore/visualization/outofcore_cloud.h>
#include <pcl/outofcore/visualization/scene.h>
#include <pcl/outofcore/visualization/viewport.h>
#include <vtkActor.h>
#include <vtkActorCollection.h>
#include <vtkActor2DCollection.h>
#include <vtkAppendPolyData.h>
#include <vtkAppendFilter.h>
#include <vtkCamera.h>
#include <vtkCameraActor.h>
#include <vtkCellArray.h>
#include <vtkCellData.h>
#include <vtkCommand.h>
#include <vtkConeSource.h>
#include <vtkCubeSource.h>
#include <vtkDataSetMapper.h>
#include <vtkHull.h>
#include <vtkInformation.h>
#include <vtkInformationStringKey.h>
#include <vtkInteractorStyleTrackballCamera.h>
#include <vtkLODActor.h>
#include <vtkMath.h>
#include <vtkMatrix4x4.h>
#include <vtkMutexLock.h>
#include <vtkObjectFactory.h>
#include <vtkPolyData.h>
#include <vtkProperty.h>
#include <vtkTextActor.h>
#include <vtkRectilinearGrid.h>
#include <vtkRenderer.h>
#include <vtkRenderWindow.h>
#include <vtkRenderWindowInteractor.h>
#include <vtkSmartPointer.h>
#include <vtkUnsignedCharArray.h>
#include <vtkInteractorStyleRubberBand3D.h>
#include <vtkParallelCoordinatesInteractorStyle.h>
#include <boost/date_time.hpp>
#include <boost/filesystem.hpp>
#include <boost/thread.hpp>
Go to the source code of this file.
Classes | |
class | KeyboardCallback |
Typedefs | |
typedef Eigen::aligned_allocator < PointT > | AlignedPointT |
typedef OutofcoreOctreeBase < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk |
typedef OutofcoreOctreeBaseNode < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk_node |
typedef boost::shared_ptr < octree_disk > | OctreeDiskPtr |
typedef PointXYZ | PointT |
Functions | |
int | main (int argc, char *argv[]) |
const int | MAX_DEPTH (-1) |
int | outofcoreViewer (boost::filesystem::path tree_root, int depth, bool display_octree=true, unsigned int gpu_cache_size=512) |
void | print_help (int argc, char **argv) |
void | renderEndCallback (vtkObject *vtkNotUsed(caller), unsigned long int vtkNotUsed(eventId), void *vtkNotUsed(clientData), void *vtkNotUsed(callData)) |
void | renderStartCallback (vtkObject *vtkNotUsed(caller), unsigned long int vtkNotUsed(eventId), void *vtkNotUsed(clientData), void *vtkNotUsed(callData)) |
void | renderTimerCallback (vtkObject *caller, unsigned long int vtkNotUsed(eventId), void *vtkNotUsed(clientData), void *vtkNotUsed(callData)) |
Variables | |
vtkSmartPointer< vtkRenderWindow > | window |
typedef Eigen::aligned_allocator<PointT> AlignedPointT |
Definition at line 93 of file outofcore_viewer.cpp.
Definition at line 87 of file outofcore_viewer.cpp.
Definition at line 88 of file outofcore_viewer.cpp.
typedef boost::shared_ptr<octree_disk> OctreeDiskPtr |
Definition at line 91 of file outofcore_viewer.cpp.
Definition at line 85 of file outofcore_viewer.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 347 of file outofcore_viewer.cpp.
const int MAX_DEPTH | ( | - | 1 | ) |
int outofcoreViewer | ( | boost::filesystem::path | tree_root, |
int | depth, | ||
bool | display_octree = true , |
||
unsigned int | gpu_cache_size = 512 |
||
) |
Definition at line 230 of file outofcore_viewer.cpp.
void print_help | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 325 of file outofcore_viewer.cpp.
void renderEndCallback | ( | vtkObject * | vtkNotUsedcaller, |
unsigned long int | vtkNotUsedeventId, | ||
void * | vtkNotUsedclientData, | ||
void * | vtkNotUsedcallData | ||
) |
Definition at line 224 of file outofcore_viewer.cpp.
void renderStartCallback | ( | vtkObject * | vtkNotUsedcaller, |
unsigned long int | vtkNotUsedeventId, | ||
void * | vtkNotUsedclientData, | ||
void * | vtkNotUsedcallData | ||
) |
Definition at line 218 of file outofcore_viewer.cpp.
void renderTimerCallback | ( | vtkObject * | caller, |
unsigned long int | vtkNotUsedeventId, | ||
void * | vtkNotUsedclientData, | ||
void * | vtkNotUsedcallData | ||
) |
Definition at line 211 of file outofcore_viewer.cpp.
vtkSmartPointer<vtkRenderWindow> window |
Definition at line 140 of file outofcore_viewer.cpp.