#include <actor_map.h>
Public Member Functions | |
CloudActor () | |
Public Attributes | |
vtkSmartPointer< vtkLODActor > | actor |
int | color_handler_index_ |
The active color handler. | |
std::vector< ColorHandlerConstPtr > | color_handlers |
int | geometry_handler_index_ |
The active geometry handler. | |
std::vector < GeometryHandlerConstPtr > | geometry_handlers |
Private Types | |
typedef PointCloudColorHandler < sensor_msgs::PointCloud2 > | ColorHandler |
typedef ColorHandler::ConstPtr | ColorHandlerConstPtr |
typedef ColorHandler::Ptr | ColorHandlerPtr |
typedef PointCloudGeometryHandler < sensor_msgs::PointCloud2 > | GeometryHandler |
typedef GeometryHandler::ConstPtr | GeometryHandlerConstPtr |
typedef GeometryHandler::Ptr | GeometryHandlerPtr |
Definition at line 49 of file actor_map.h.
typedef PointCloudColorHandler<sensor_msgs::PointCloud2> pcl_visualization::CloudActor::ColorHandler [private] |
Definition at line 55 of file actor_map.h.
typedef ColorHandler::ConstPtr pcl_visualization::CloudActor::ColorHandlerConstPtr [private] |
Definition at line 57 of file actor_map.h.
typedef ColorHandler::Ptr pcl_visualization::CloudActor::ColorHandlerPtr [private] |
Definition at line 56 of file actor_map.h.
typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2> pcl_visualization::CloudActor::GeometryHandler [private] |
Definition at line 51 of file actor_map.h.
Definition at line 53 of file actor_map.h.
typedef GeometryHandler::Ptr pcl_visualization::CloudActor::GeometryHandlerPtr [private] |
Definition at line 52 of file actor_map.h.
pcl_visualization::CloudActor::CloudActor | ( | ) | [inline] |
Definition at line 61 of file actor_map.h.
vtkSmartPointer<vtkLODActor> pcl_visualization::CloudActor::actor |
Definition at line 63 of file actor_map.h.
The active color handler.
Definition at line 68 of file actor_map.h.
Definition at line 65 of file actor_map.h.
The active geometry handler.
Definition at line 71 of file actor_map.h.
Definition at line 64 of file actor_map.h.