Base handler class for PointCloud geometry. More...
#include <point_cloud_handlers.h>

| Public Types | |
| typedef boost::shared_ptr < const PointCloudGeometryHandler < PointT > > | ConstPtr | 
| typedef pcl::PointCloud< PointT > | PointCloud | 
| typedef PointCloud::ConstPtr | PointCloudConstPtr | 
| typedef PointCloud::Ptr | PointCloudPtr | 
| typedef boost::shared_ptr < PointCloudGeometryHandler < PointT > > | Ptr | 
| Public Member Functions | |
| virtual std::string | getFieldName () const =0 | 
| Abstract getFieldName method. | |
| virtual void | getGeometry (vtkSmartPointer< vtkPoints > &points) const =0 | 
| 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. | |
| Ptr | makeShared () const | 
| 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. The PointCloud must be read from disk as PCD or converted from sensor_msgs/PointCloud2 for this to work! | |
Base handler class for PointCloud geometry.
Definition at line 59 of file point_cloud_handlers.h.
| typedef boost::shared_ptr<const PointCloudGeometryHandler<PointT> > pcl_visualization::PointCloudGeometryHandler< PointT >::ConstPtr | 
Reimplemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
Definition at line 67 of file point_cloud_handlers.h.
| typedef pcl::PointCloud<PointT> pcl_visualization::PointCloudGeometryHandler< PointT >::PointCloud | 
Reimplemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
Definition at line 62 of file point_cloud_handlers.h.
| typedef PointCloud::ConstPtr pcl_visualization::PointCloudGeometryHandler< PointT >::PointCloudConstPtr | 
Reimplemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
Definition at line 64 of file point_cloud_handlers.h.
| typedef PointCloud::Ptr pcl_visualization::PointCloudGeometryHandler< PointT >::PointCloudPtr | 
Reimplemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
Definition at line 63 of file point_cloud_handlers.h.
| typedef boost::shared_ptr<PointCloudGeometryHandler<PointT> > pcl_visualization::PointCloudGeometryHandler< PointT >::Ptr | 
Reimplemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
Definition at line 66 of file point_cloud_handlers.h.
| pcl_visualization::PointCloudGeometryHandler< PointT >::PointCloudGeometryHandler | ( | const PointCloud & | cloud | ) |  [inline] | 
Constructor.
Definition at line 72 of file point_cloud_handlers.h.
| virtual std::string pcl_visualization::PointCloudGeometryHandler< PointT >::getFieldName | ( | ) | const  [pure virtual] | 
Abstract getFieldName method.
Implemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
| virtual void pcl_visualization::PointCloudGeometryHandler< PointT >::getGeometry | ( | vtkSmartPointer< vtkPoints > & | points | ) | const  [pure virtual] | 
Obtain the actual point geometry for the input dataset as a vtk pointset.
| points | the resultant geometry | 
Implemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
| virtual std::string pcl_visualization::PointCloudGeometryHandler< PointT >::getName | ( | ) | const  [pure virtual] | 
Abstract getName method.
Implemented in pcl_visualization::PointCloudGeometryHandlerXYZ< PointT >, pcl_visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >, and pcl_visualization::PointCloudGeometryHandlerCustom< PointT >.
| bool pcl_visualization::PointCloudGeometryHandler< PointT >::isCapable | ( | ) | const  [inline] | 
Return whether this handler is capable of handling the input data or not.
Definition at line 84 of file point_cloud_handlers.h.
| Ptr pcl_visualization::PointCloudGeometryHandler< PointT >::makeShared | ( | ) | const  [inline] | 
Definition at line 69 of file point_cloud_handlers.h.
| bool pcl_visualization::PointCloudGeometryHandler< PointT >::capable_  [protected] | 
True if this handler is capable of handling the input data, false otherwise.
Definition at line 96 of file point_cloud_handlers.h.
| PointCloudPtr pcl_visualization::PointCloudGeometryHandler< PointT >::cloud_  [protected] | 
A pointer to the input dataset.
Definition at line 93 of file point_cloud_handlers.h.
| int pcl_visualization::PointCloudGeometryHandler< PointT >::field_x_idx_  [protected] | 
The index of the field holding the X data.
Definition at line 99 of file point_cloud_handlers.h.
| int pcl_visualization::PointCloudGeometryHandler< PointT >::field_y_idx_  [protected] | 
The index of the field holding the Y data.
Definition at line 102 of file point_cloud_handlers.h.
| int pcl_visualization::PointCloudGeometryHandler< PointT >::field_z_idx_  [protected] | 
The index of the field holding the Z data.
Definition at line 105 of file point_cloud_handlers.h.
| std::vector<sensor_msgs::PointField> pcl_visualization::PointCloudGeometryHandler< PointT >::fields_  [protected] | 
The list of fields available for this PointCloud. The PointCloud must be read from disk as PCD or converted from sensor_msgs/PointCloud2 for this to work!
Definition at line 109 of file point_cloud_handlers.h.