Point Cloud Library (PCL)
1.14.1-dev
|
Base Handler class for PointCloud colors. More...
#include <pcl/visualization/point_cloud_color_handlers.h>
Public Types | |
using | PointCloud = pcl::PointCloud< PointT > |
using | PointCloudPtr = typename PointCloud::Ptr |
using | PointCloudConstPtr = typename PointCloud::ConstPtr |
using | Ptr = shared_ptr< PointCloudColorHandler< PointT > > |
using | ConstPtr = shared_ptr< const PointCloudColorHandler< PointT > > |
Public Member Functions | |
PointCloudColorHandler () | |
Constructor. More... | |
PointCloudColorHandler (const PointCloudConstPtr &cloud) | |
Constructor. More... | |
virtual | ~PointCloudColorHandler ()=default |
Destructor. More... | |
bool | isCapable () const |
Check if this handler is capable of handling the input data or not. More... | |
virtual std::string | getName () const =0 |
Abstract getName method. More... | |
virtual std::string | getFieldName () const =0 |
Abstract getFieldName method. More... | |
virtual vtkSmartPointer< vtkDataArray > | getColor () const =0 |
Obtain the actual color for the input dataset as a VTK data array. More... | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Set the input cloud to be used. More... | |
Protected Attributes | |
PointCloudConstPtr | cloud_ |
A pointer to the input dataset. More... | |
bool | capable_ |
True if this handler is capable of handling the input data, false otherwise. More... | |
int | field_idx_ |
The index of the field holding the data that represents the color. More... | |
std::vector< pcl::PCLPointField > | fields_ |
The list of fields available for this PointCloud. More... | |
Base Handler class for PointCloud colors.
Definition at line 65 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandler< PointT >::ConstPtr = shared_ptr<const PointCloudColorHandler<PointT> > |
Definition at line 73 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandler< PointT >::PointCloud = pcl::PointCloud<PointT> |
Definition at line 68 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandler< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
Definition at line 70 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandler< PointT >::PointCloudPtr = typename PointCloud::Ptr |
Definition at line 69 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandler< PointT >::Ptr = shared_ptr<PointCloudColorHandler<PointT> > |
Definition at line 72 of file point_cloud_color_handlers.h.
|
inline |
Constructor.
Definition at line 76 of file point_cloud_color_handlers.h.
|
inline |
Constructor.
Definition at line 81 of file point_cloud_color_handlers.h.
|
virtualdefault |
Destructor.
|
pure virtual |
Obtain the actual color for the input dataset as a VTK data array.
Deriving handlers should override this method.
Implemented in pcl::visualization::PointCloudColorHandlerLabelField< PointT >, pcl::visualization::PointCloudColorHandlerRGBAField< PointT >, pcl::visualization::PointCloudColorHandlerGenericField< PointT >, pcl::visualization::PointCloudColorHandlerHSVField< PointT >, pcl::visualization::PointCloudColorHandlerRGBField< PointT >, pcl::visualization::PointCloudColorHandlerCustom< PointT >, pcl::visualization::PointCloudColorHandlerRandom< PointT >, and pcl::visualization::PointCloudColorHandlerRGBHack< PointT >.
Referenced by pcl::visualization::PCLVisualizer::updatePointCloud().
|
pure virtual |
Abstract getFieldName method.
Implemented in pcl::visualization::PointCloudColorHandlerLabelField< PointT >, pcl::visualization::PointCloudColorHandlerRGBAField< PointT >, pcl::visualization::PointCloudColorHandlerGenericField< PointT >, pcl::visualization::PointCloudColorHandlerHSVField< PointT >, pcl::visualization::PointCloudColorHandlerRGBField< PointT >, pcl::visualization::PointCloudColorHandlerCustom< PointT >, and pcl::visualization::PointCloudColorHandlerRandom< PointT >.
|
pure virtual |
Abstract getName method.
Implemented in pcl::visualization::PointCloudColorHandlerLabelField< PointT >, pcl::visualization::PointCloudColorHandlerRGBAField< PointT >, pcl::visualization::PointCloudColorHandlerGenericField< PointT >, pcl::visualization::PointCloudColorHandlerHSVField< PointT >, pcl::visualization::PointCloudColorHandlerRGBField< PointT >, pcl::visualization::PointCloudColorHandlerCustom< PointT >, and pcl::visualization::PointCloudColorHandlerRandom< PointT >.
|
inline |
Check if this handler is capable of handling the input data or not.
Definition at line 90 of file point_cloud_color_handlers.h.
References pcl::visualization::PointCloudColorHandler< PointT >::capable_.
|
inlinevirtual |
Set the input cloud to be used.
[in] | cloud | the input cloud to be used by the handler |
Reimplemented in pcl::visualization::PointCloudColorHandlerLabelField< PointT >, pcl::visualization::PointCloudColorHandlerRGBAField< PointT >, pcl::visualization::PointCloudColorHandlerGenericField< PointT >, and pcl::visualization::PointCloudColorHandlerRGBField< PointT >.
Definition at line 111 of file point_cloud_color_handlers.h.
References pcl::visualization::PointCloudColorHandler< PointT >::cloud_.
Referenced by pcl::visualization::PointCloudColorHandlerRGBField< PointT >::setInputCloud(), pcl::visualization::PointCloudColorHandlerGenericField< PointT >::setInputCloud(), pcl::visualization::PointCloudColorHandlerRGBAField< PointT >::setInputCloud(), and pcl::visualization::PointCloudColorHandlerLabelField< PointT >::setInputCloud().
|
protected |
True if this handler is capable of handling the input data, false otherwise.
Definition at line 123 of file point_cloud_color_handlers.h.
Referenced by pcl::visualization::PointCloudColorHandlerRGBHack< PointT >::getColor(), pcl::visualization::PointCloudColorHandler< PointT >::isCapable(), pcl::visualization::PointCloudColorHandlerCustom< PointT >::PointCloudColorHandlerCustom(), pcl::visualization::PointCloudColorHandlerGenericField< PointT >::PointCloudColorHandlerGenericField(), pcl::visualization::PointCloudColorHandlerHSVField< PointT >::PointCloudColorHandlerHSVField(), pcl::visualization::PointCloudColorHandlerLabelField< PointT >::PointCloudColorHandlerLabelField(), pcl::visualization::PointCloudColorHandlerRandom< PointT >::PointCloudColorHandlerRandom(), pcl::visualization::PointCloudColorHandlerRGBAField< PointT >::PointCloudColorHandlerRGBAField(), pcl::visualization::PointCloudColorHandlerRGBField< PointT >::PointCloudColorHandlerRGBField(), and pcl::visualization::PointCloudColorHandlerRGBHack< PointT >::PointCloudColorHandlerRGBHack().
|
protected |
A pointer to the input dataset.
Definition at line 118 of file point_cloud_color_handlers.h.
Referenced by pcl::visualization::PointCloudColorHandlerRGBHack< PointT >::getColor(), and pcl::visualization::PointCloudColorHandler< PointT >::setInputCloud().
|
protected |
The index of the field holding the data that represents the color.
Definition at line 126 of file point_cloud_color_handlers.h.
Referenced by pcl::visualization::PointCloudColorHandlerHSVField< PointT >::PointCloudColorHandlerHSVField().
|
protected |
The list of fields available for this PointCloud.
Definition at line 129 of file point_cloud_color_handlers.h.
Referenced by pcl::visualization::PointCloudColorHandlerHSVField< PointT >::PointCloudColorHandlerHSVField().