Classes | Namespaces
point_cloud_handlers.h File Reference
#include <pcl/visualization/common/common.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/common/io.h>
#include <pcl/visualization/vtk.h>
#include <pcl/visualization/impl/point_cloud_handlers.hpp>
Include dependency graph for point_cloud_handlers.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  pcl::visualization::PointCloudColorHandler< PointT >
 Base Handler class for PointCloud colors. More...
class  pcl::visualization::PointCloudColorHandler< sensor_msgs::PointCloud2 >
 Base Handler class for PointCloud colors. More...
class  pcl::visualization::PointCloudColorHandlerCustom< PointT >
 Handler for predefined user colors. The color at each point will be drawn as the use given R, G, B values. More...
class  pcl::visualization::PointCloudColorHandlerCustom< sensor_msgs::PointCloud2 >
 Handler for predefined user colors. The color at each point will be drawn as the use given R, G, B values. More...
class  pcl::visualization::PointCloudColorHandlerGenericField< PointT >
 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. More...
class  pcl::visualization::PointCloudColorHandlerGenericField< sensor_msgs::PointCloud2 >
 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. More...
class  pcl::visualization::PointCloudColorHandlerHSVField< PointT >
 HSV handler class for colors. Uses the data present in the "h", "s", "v" fields as the color at each point. More...
class  pcl::visualization::PointCloudColorHandlerHSVField< sensor_msgs::PointCloud2 >
 HSV handler class for colors. Uses the data present in the "h", "s", "v" fields as the color at each point. More...
class  pcl::visualization::PointCloudColorHandlerRandom< PointT >
 Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) More...
class  pcl::visualization::PointCloudColorHandlerRandom< sensor_msgs::PointCloud2 >
 Handler for random PointCloud colors (i.e., R, G, B will be randomly chosen) More...
class  pcl::visualization::PointCloudColorHandlerRGBField< PointT >
 RGB handler class for colors. Uses the data present in the "rgb" or "rgba" fields as the color at each point. More...
class  pcl::visualization::PointCloudColorHandlerRGBField< sensor_msgs::PointCloud2 >
 RGB handler class for colors. Uses the data present in the "rgb" or "rgba" fields as the color at each point. More...
class  pcl::visualization::PointCloudGeometryHandler< PointT >
 Base handler class for PointCloud geometry. More...
class  pcl::visualization::PointCloudGeometryHandler< sensor_msgs::PointCloud2 >
 Base handler class for PointCloud geometry. More...
class  pcl::visualization::PointCloudGeometryHandlerCustom< PointT >
 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...
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. More...
class  pcl::visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >
 Surface normal handler class for PointCloud geometry. Given an input dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is extracted and dislayed on screen as XYZ data. More...
class  pcl::visualization::PointCloudGeometryHandlerSurfaceNormal< sensor_msgs::PointCloud2 >
 Surface normal handler class for PointCloud geometry. Given an input dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is extracted and dislayed on screen as XYZ data. More...
class  pcl::visualization::PointCloudGeometryHandlerXYZ< PointT >
 XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ data present in fields "x", "y", and "z" is extracted and displayed on screen. More...
class  pcl::visualization::PointCloudGeometryHandlerXYZ< sensor_msgs::PointCloud2 >
 XYZ handler class for PointCloud geometry. Given an input dataset, all XYZ data present in fields "x", "y", and "z" is extracted and displayed on screen. More...

Namespaces

namespace  pcl
namespace  pcl::visualization


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:13