pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 > Class Template Reference

Base handler class for PointCloud geometry. More...

#include <point_cloud_handlers.h>

Inheritance diagram for pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
PointCloudGeometryHandler
< PointCloud > > 
ConstPtr
typedef sensor_msgs::PointCloud2 PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef boost::shared_ptr
< PointCloudGeometryHandler
< PointCloud > > 
Ptr

Public Member Functions

virtual std::string getFieldName () const =0
 Abstract getFieldName method.
virtual void getGeometry (vtkSmartPointer< vtkPoints > &points) const
 Obtain the actual point geometry for the input dataset as a vtk pointset.
virtual std::string getName () const =0
 Abstract getName method.
bool isCapable () const
 Return whether this handler is capable of handling the input data or not.
 PointCloudGeometryHandler (const PointCloud &cloud)
 Constructor.

Protected Attributes

bool capable_
 True if this handler is capable of handling the input data, false otherwise.
PointCloudPtr cloud_
 A pointer to the input dataset.
int field_x_idx_
 The index of the field holding the X data.
int field_y_idx_
 The index of the field holding the Y data.
int field_z_idx_
 The index of the field holding the Z data.
std::vector
< sensor_msgs::PointField > 
fields_
 The list of fields available for this PointCloud.

Detailed Description

template<>
class pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >

Base handler class for PointCloud geometry.

Definition at line 231 of file point_cloud_handlers.h.


Member Typedef Documentation

typedef boost::shared_ptr<const PointCloudGeometryHandler<PointCloud> > pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::ConstPtr
typedef sensor_msgs::PointCloud2 pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::PointCloud
typedef PointCloud::ConstPtr pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::PointCloudConstPtr
typedef PointCloud::Ptr pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::PointCloudPtr
typedef boost::shared_ptr<PointCloudGeometryHandler<PointCloud> > pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::Ptr

Constructor & Destructor Documentation

pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::PointCloudGeometryHandler ( const PointCloud cloud  )  [inline]

Constructor.

Definition at line 242 of file point_cloud_handlers.h.


Member Function Documentation

virtual std::string pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::getFieldName (  )  const [pure virtual]
void pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::getGeometry ( vtkSmartPointer< vtkPoints > &  points  )  const [virtual]

Obtain the actual point geometry for the input dataset as a vtk pointset.

Parameters:
points the resultant geometry

Definition at line 254 of file point_cloud_handlers.cpp.

virtual std::string pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::getName (  )  const [pure virtual]
bool pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::isCapable (  )  const [inline]

Return whether this handler is capable of handling the input data or not.

Definition at line 255 of file point_cloud_handlers.h.


Member Data Documentation

bool pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::capable_ [protected]

True if this handler is capable of handling the input data, false otherwise.

Definition at line 267 of file point_cloud_handlers.h.

PointCloudPtr pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::cloud_ [protected]

A pointer to the input dataset.

Definition at line 264 of file point_cloud_handlers.h.

int pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::field_x_idx_ [protected]

The index of the field holding the X data.

Definition at line 270 of file point_cloud_handlers.h.

int pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::field_y_idx_ [protected]

The index of the field holding the Y data.

Definition at line 273 of file point_cloud_handlers.h.

int pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::field_z_idx_ [protected]

The index of the field holding the Z data.

Definition at line 276 of file point_cloud_handlers.h.

std::vector<sensor_msgs::PointField> pcl_visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >::fields_ [protected]

The list of fields available for this PointCloud.

Definition at line 279 of file point_cloud_handlers.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pcl_visualization
Author(s): Radu Bogdan Rusu, Bastian Steder, Ethan Rublee
autogenerated on Fri Jan 11 09:59:20 2013