Public Types | Public Member Functions | Private Attributes
pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 > Class Template Reference

Custom handler class for PointCloud geometry. Given an input dataset and three user defined fields, all data present in them is extracted and displayed on screen as XYZ data. More...

#include <point_cloud_handlers.h>

Inheritance diagram for pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Types

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

Public Member Functions

virtual std::string getFieldName () const
 Get the name of the field used.
virtual std::string getName () const
 Class getName method.
 PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud, const std::string &x_field_name, const std::string &y_field_name, const std::string &z_field_name)
 Constructor.
virtual ~PointCloudGeometryHandlerCustom ()
 Destructor.

Private Attributes

std::string field_name_
 Name of the field used to create the geometry handler.

Detailed Description

template<>
class pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >

Custom handler class for PointCloud geometry. Given an input dataset and three user defined fields, all data present in them is extracted and displayed on screen as XYZ data.

Definition at line 390 of file point_cloud_handlers.h.


Member Typedef Documentation

typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2>::PointCloud pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::PointCloud

Constructor & Destructor Documentation

pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::PointCloudGeometryHandlerCustom ( const PointCloudConstPtr cloud,
const std::string &  x_field_name,
const std::string &  y_field_name,
const std::string &  z_field_name 
)

Constructor.

Definition at line 601 of file point_cloud_handlers.cpp.

virtual pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::~PointCloudGeometryHandlerCustom ( ) [inline, virtual]

Destructor.

Definition at line 404 of file point_cloud_handlers.h.


Member Function Documentation

virtual std::string pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::getFieldName ( ) const [inline, virtual]

Get the name of the field used.

Implements pcl::visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >.

Definition at line 412 of file point_cloud_handlers.h.

virtual std::string pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::getName ( ) const [inline, virtual]

Class getName method.

Implements pcl::visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >.

Definition at line 408 of file point_cloud_handlers.h.


Member Data Documentation

std::string pcl::visualization::PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 >::field_name_ [private]

Name of the field used to create the geometry handler.

Definition at line 416 of file point_cloud_handlers.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:40