#include <actor_map.h>
Public Member Functions | |
| CloudActor () | |
| virtual | ~CloudActor () |
Public Attributes | |
| vtkSmartPointer< vtkLODActor > | actor |
| The actor holding the data to render. | |
| vtkSmartPointer< vtkIdTypeArray > | cells |
| Internal cell array. Used for optimizing updatePointCloud. | |
| int | color_handler_index_ |
| The active color handler. | |
| std::vector< ColorHandlerConstPtr > | color_handlers |
| A vector of color handlers that can be used for rendering the data. | |
| int | geometry_handler_index_ |
| The active geometry handler. | |
| std::vector < GeometryHandlerConstPtr > | geometry_handlers |
| A vector of geometry handlers that can be used for rendering the data. | |
| vtkSmartPointer< vtkMatrix4x4 > | viewpoint_transformation_ |
| The viewpoint transformation matrix. | |
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 51 of file actor_map.h.
typedef PointCloudColorHandler<sensor_msgs::PointCloud2> pcl::visualization::CloudActor::ColorHandler [private] |
Definition at line 57 of file actor_map.h.
typedef ColorHandler::ConstPtr pcl::visualization::CloudActor::ColorHandlerConstPtr [private] |
Definition at line 59 of file actor_map.h.
typedef ColorHandler::Ptr pcl::visualization::CloudActor::ColorHandlerPtr [private] |
Definition at line 58 of file actor_map.h.
typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2> pcl::visualization::CloudActor::GeometryHandler [private] |
Definition at line 53 of file actor_map.h.
Definition at line 55 of file actor_map.h.
typedef GeometryHandler::Ptr pcl::visualization::CloudActor::GeometryHandlerPtr [private] |
Definition at line 54 of file actor_map.h.
| pcl::visualization::CloudActor::CloudActor | ( | ) | [inline] |
Definition at line 62 of file actor_map.h.
| virtual pcl::visualization::CloudActor::~CloudActor | ( | ) | [inline, virtual] |
Definition at line 64 of file actor_map.h.
| vtkSmartPointer<vtkLODActor> pcl::visualization::CloudActor::actor |
The actor holding the data to render.
Definition at line 71 of file actor_map.h.
| vtkSmartPointer<vtkIdTypeArray> pcl::visualization::CloudActor::cells |
Internal cell array. Used for optimizing updatePointCloud.
Definition at line 89 of file actor_map.h.
The active color handler.
Definition at line 80 of file actor_map.h.
A vector of color handlers that can be used for rendering the data.
Definition at line 77 of file actor_map.h.
The active geometry handler.
Definition at line 83 of file actor_map.h.
A vector of geometry handlers that can be used for rendering the data.
Definition at line 74 of file actor_map.h.
| vtkSmartPointer<vtkMatrix4x4> pcl::visualization::CloudActor::viewpoint_transformation_ |
The viewpoint transformation matrix.
Definition at line 86 of file actor_map.h.