Classes | Public Types | Public Slots | Public Member Functions | Private Types | Private Slots | Private Member Functions | Private Attributes
pcl::ihs::OfflineIntegration Class Reference

Read the clouds and transformations from files and integrate them into one common model. More...

#include <offline_integration.h>

Inheritance diagram for pcl::ihs::OfflineIntegration:
Inheritance graph
[legend]

List of all members.

Classes

class  ComputationFPS
 Helper object for the computation thread. Please have a look at the documentation of calcFPS. More...
class  VisualizationFPS
 Helper object for the visualization thread. Please have a look at the documentation of calcFPS. More...

Public Types

typedef pcl::ihs::OpenGLViewer Base
typedef
pcl::ihs::OfflineIntegration 
Self

Public Slots

void start ()
 Start the procedure from a path.

Public Member Functions

 OfflineIntegration (Base *parent=0)
 Constructor.
 ~OfflineIntegration ()
 Destructor.

Private Types

typedef pcl::PointCloud
< PointXYZRGBA
CloudXYZRGBA
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr
typedef pcl::PointCloud
< PointXYZRGBNormal
CloudXYZRGBNormal
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr
typedef pcl::ihs::Integration Integration
typedef boost::shared_ptr
< const Integration
IntegrationConstPtr
typedef boost::shared_ptr
< Integration
IntegrationPtr
typedef pcl::ihs::Mesh Mesh
typedef pcl::ihs::MeshConstPtr MeshConstPtr
typedef pcl::ihs::MeshPtr MeshPtr
typedef
pcl::IntegralImageNormalEstimation
< PointXYZRGBA,
PointXYZRGBNormal
NormalEstimation
typedef boost::shared_ptr
< const NormalEstimation
NormalEstimationConstPtr
typedef boost::shared_ptr
< NormalEstimation
NormalEstimationPtr
typedef pcl::PointXYZRGBA PointXYZRGBA
typedef pcl::PointXYZRGBNormal PointXYZRGBNormal

Private Slots

void computationThread ()
 Loads in new data.

Private Member Functions

bool getFilesFromDirectory (const std::string path_dir, const std::string extension, std::vector< std::string > &files) const
 Get a list of files with from a given directory.
void keyPressEvent (QKeyEvent *event)
bool load (const std::string &filename, CloudXYZRGBNormalPtr &cloud, Eigen::Matrix4f &T) const
 Load the cloud and transformation from the files and compute the normals.
bool loadTransform (const std::string &filename, Eigen::Matrix4f &transform) const
 Load the transformation matrix from the given file.
void paintEvent (QPaintEvent *event)

Private Attributes

ComputationFPS computation_fps_
 Please have a look at the documentation of ComputationFPS.
bool destructor_called_
 Prevent the application to crash while closing.
IntegrationPtr integration_
 Integrate the data cloud into a common model.
MeshPtr mesh_model_
 Model to which new data is registered to (stored as a mesh).
boost::mutex mutex_
 Synchronization.
boost::mutex mutex_quit_
 Wait until the data finished processing.
NormalEstimationPtr normal_estimation_
 Compute the normals for the input clouds.
std::string path_dir_
 Path to the pcd and transformation files.
VisualizationFPS visualization_fps_
 Please have a look at the documentation of VisualizationFPS.

Detailed Description

Read the clouds and transformations from files and integrate them into one common model.

Todo:
Add Documentation

Definition at line 80 of file offline_integration.h.


Member Typedef Documentation

Definition at line 86 of file offline_integration.h.

Definition at line 110 of file offline_integration.h.

Definition at line 112 of file offline_integration.h.

Definition at line 111 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 115 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 117 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 116 of file offline_integration.h.

Definition at line 123 of file offline_integration.h.

typedef boost::shared_ptr<const Integration> pcl::ihs::OfflineIntegration::IntegrationConstPtr [private]

Definition at line 125 of file offline_integration.h.

typedef boost::shared_ptr<Integration> pcl::ihs::OfflineIntegration::IntegrationPtr [private]

Definition at line 124 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 119 of file offline_integration.h.

typedef pcl::ihs::MeshConstPtr pcl::ihs::OfflineIntegration::MeshConstPtr [private]

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 121 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 120 of file offline_integration.h.

Definition at line 127 of file offline_integration.h.

Definition at line 129 of file offline_integration.h.

Definition at line 128 of file offline_integration.h.

Definition at line 109 of file offline_integration.h.

Reimplemented from pcl::ihs::OpenGLViewer.

Definition at line 114 of file offline_integration.h.

Definition at line 87 of file offline_integration.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 61 of file offline_integration.cpp.

Destructor.

Definition at line 86 of file offline_integration.cpp.


Member Function Documentation

Loads in new data.

Definition at line 112 of file offline_integration.cpp.

bool pcl::ihs::OfflineIntegration::getFilesFromDirectory ( const std::string  path_dir,
const std::string  extension,
std::vector< std::string > &  files 
) const [private]

Get a list of files with from a given directory.

Parameters:
[in]path_dirPath to search for the files.
[in]extensionFile extension (must start with a dot). E.g. '.pcd'.
[out]filesPaths to the files.
Returns:
True if success.

Definition at line 188 of file offline_integration.cpp.

void pcl::ihs::OfflineIntegration::keyPressEvent ( QKeyEvent *  event) [private]
bool pcl::ihs::OfflineIntegration::load ( const std::string filename,
CloudXYZRGBNormalPtr cloud,
Eigen::Matrix4f &  T 
) const [private]

Load the cloud and transformation from the files and compute the normals.

Parameters:
[in]filenamePath to the pcd file.
[out]cloudCloud with computed normals.
[out]TLoaded transformation.
Returns:
True if success.

Definition at line 257 of file offline_integration.cpp.

bool pcl::ihs::OfflineIntegration::loadTransform ( const std::string filename,
Eigen::Matrix4f &  transform 
) const [private]

Load the transformation matrix from the given file.

Parameters:
[in]filenamePath to the file.
[out]transformThe loaded transform.
Returns:
True if success.

Definition at line 222 of file offline_integration.cpp.

void pcl::ihs::OfflineIntegration::paintEvent ( QPaintEvent *  event) [private, virtual]

Start the procedure from a path.

Definition at line 96 of file offline_integration.cpp.


Member Data Documentation

Please have a look at the documentation of ComputationFPS.

Definition at line 200 of file offline_integration.h.

Prevent the application to crash while closing.

Definition at line 218 of file offline_integration.h.

Integrate the data cloud into a common model.

Definition at line 215 of file offline_integration.h.

Model to which new data is registered to (stored as a mesh).

Definition at line 209 of file offline_integration.h.

boost::mutex pcl::ihs::OfflineIntegration::mutex_ [private]

Synchronization.

Definition at line 194 of file offline_integration.h.

Wait until the data finished processing.

Definition at line 197 of file offline_integration.h.

Compute the normals for the input clouds.

Definition at line 212 of file offline_integration.h.

Path to the pcd and transformation files.

Definition at line 206 of file offline_integration.h.

Please have a look at the documentation of VisualizationFPS.

Definition at line 203 of file offline_integration.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:58