Point Cloud Library (PCL)
1.10.0
|
Generic field handler class for colors. More...
#include <pcl/visualization/point_cloud_color_handlers.h>
Public Types | |
using | Ptr = shared_ptr< PointCloudColorHandlerGenericField< PointT > > |
using | ConstPtr = shared_ptr< const PointCloudColorHandlerGenericField< PointT > > |
![]() | |
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 | |
PointCloudColorHandlerGenericField (const std::string &field_name) | |
Constructor. More... | |
PointCloudColorHandlerGenericField (const PointCloudConstPtr &cloud, const std::string &field_name) | |
Constructor. More... | |
virtual | ~PointCloudColorHandlerGenericField () |
Destructor. More... | |
virtual std::string | getFieldName () const |
Get the name of the field used. More... | |
vtkSmartPointer< vtkDataArray > | getColor () const override |
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... | |
![]() | |
PointCloudColorHandler () | |
Constructor. More... | |
PointCloudColorHandler (const PointCloudConstPtr &cloud) | |
Constructor. More... | |
virtual | ~PointCloudColorHandler () |
Destructor. More... | |
bool | isCapable () const |
Check if this handler is capable of handling the input data or not. More... | |
virtual bool | getColor (vtkSmartPointer< vtkDataArray > &scalars) const |
Obtain the actual color for the input dataset as a VTK data array. More... | |
Protected Member Functions | |
virtual std::string | getName () const |
Class getName method. More... | |
Additional Inherited Members | |
![]() | |
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... | |
Generic field handler class for colors.
Uses an user given field to extract 1D data and display the color at each point using a min-max lookup table.
Definition at line 377 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandlerGenericField< PointT >::ConstPtr = shared_ptr<const PointCloudColorHandlerGenericField<PointT> > |
Definition at line 385 of file point_cloud_color_handlers.h.
using pcl::visualization::PointCloudColorHandlerGenericField< PointT >::Ptr = shared_ptr<PointCloudColorHandlerGenericField<PointT> > |
Definition at line 384 of file point_cloud_color_handlers.h.
|
inline |
Constructor.
Definition at line 388 of file point_cloud_color_handlers.h.
References pcl::visualization::PointCloudColorHandler< PointT >::capable_.
|
inline |
Constructor.
Definition at line 395 of file point_cloud_color_handlers.h.
References pcl::visualization::PointCloudColorHandlerGenericField< PointT >::setInputCloud().
|
inlinevirtual |
Destructor.
Definition at line 404 of file point_cloud_color_handlers.h.
|
overridevirtual |
Obtain the actual color for the input dataset as a VTK data array.
Deriving handlers should override this method. The default implementation is provided only for backwards compatibility with handlers that were written before PCL 1.10.0 and will be removed in future.
Reimplemented from pcl::visualization::PointCloudColorHandler< PointT >.
Definition at line 377 of file point_cloud_color_handlers.hpp.
References pcl::getFieldSize().
|
inlinevirtual |
Get the name of the field used.
Implements pcl::visualization::PointCloudColorHandler< PointT >.
Definition at line 407 of file point_cloud_color_handlers.h.
|
inlineprotectedvirtual |
Class getName method.
Implements pcl::visualization::PointCloudColorHandler< PointT >.
Definition at line 423 of file point_cloud_color_handlers.h.
|
virtual |
Set the input cloud to be used.
[in] | cloud | the input cloud to be used by the handler |
Reimplemented from pcl::visualization::PointCloudColorHandler< PointT >.
Definition at line 364 of file point_cloud_color_handlers.hpp.
References pcl::visualization::PointCloudColorHandler< PointT >::setInputCloud().
Referenced by pcl::visualization::PointCloudColorHandlerGenericField< PointT >::PointCloudColorHandlerGenericField().