$search
Classes | |
class | Camera |
Camera class holds a set of camera parameters together with the window pos/size. More... | |
class | CloudActor |
class | CloudViewer |
Dead simple/easy to use class for a point cloud. More... | |
class | FloatImageUtils |
class | FPSCallback |
class | ImageWidgetWX |
class | PCLHistogramVisualizer |
PCL histogram visualizer main class. More... | |
class | PCLHistogramVisualizerInteractorStyle |
PCL histogram visualizer interactory style class. More... | |
class | PCLVisualizer |
PCL Visualizer main class. More... | |
class | PCLVisualizerInteractor |
The PCLVisualizer interactor. More... | |
class | PCLVisualizerInteractorStyle |
PCL Visualizer interactory style class. More... | |
class | PointCloudColorHandler |
Base Handler class for PointCloud colors. More... | |
class | PointCloudColorHandler< sensor_msgs::PointCloud2 > |
Base Handler class for PointCloud colors. More... | |
class | PointCloudColorHandlerCustom |
Handler for predefined user colors. More... | |
class | PointCloudColorHandlerCustom< sensor_msgs::PointCloud2 > |
Handler for predefined user colors. More... | |
class | PointCloudColorHandlerGenericField |
Generic field handler class for colors. More... | |
class | PointCloudColorHandlerGenericField< sensor_msgs::PointCloud2 > |
Generic field handler class for colors. More... | |
class | PointCloudColorHandlerRandom |
Handler for random PointCloud colors. More... | |
class | PointCloudColorHandlerRandom< sensor_msgs::PointCloud2 > |
Handler for random PointCloud colors. More... | |
class | PointCloudColorHandlerRGBField |
RGB handler class for colors. More... | |
class | PointCloudColorHandlerRGBField< sensor_msgs::PointCloud2 > |
RGB handler class for colors. More... | |
class | PointCloudGeometryHandler |
Base handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandler< sensor_msgs::PointCloud2 > |
Base handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerCustom |
Custom handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerCustom< sensor_msgs::PointCloud2 > |
Custom handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerSurfaceNormal |
Surface normal handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerSurfaceNormal< sensor_msgs::PointCloud2 > |
Surface normal handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerXYZ |
XYZ handler class for PointCloud geometry. More... | |
class | PointCloudGeometryHandlerXYZ< sensor_msgs::PointCloud2 > |
XYZ handler class for PointCloud geometry. More... | |
class | RangeImageVisualizer |
class | RenWinInteract |
Typedefs | |
typedef std::map< std::string, CloudActor > | CloudActorMap |
typedef std::map< std::string, RenWinInteract > | RenWinInteractMap |
typedef std::map< std::string, vtkSmartPointer< vtkProp > > | ShapeActorMap |
Enumerations | |
enum | RenderingProperties { PCL_VISUALIZER_POINT_SIZE, PCL_VISUALIZER_OPACITY, PCL_VISUALIZER_LINE_WIDTH, PCL_VISUALIZER_FONT_SIZE, PCL_VISUALIZER_COLOR } |
Functions | |
vtkSmartPointer< vtkDataSet > | create2DCircle (const pcl::ModelCoefficients &coefficients, double z=0.0) |
Create a 2d circle shape from a set of model coefficients. | |
vtkSmartPointer< vtkDataSet > | createCone (const pcl::ModelCoefficients &coefficients) |
Create a cone shape from a set of model coefficients. | |
vtkSmartPointer< vtkDataSet > | createCylinder (const pcl::ModelCoefficients &coefficients, int numsides=30) |
Create a cylinder shape from a set of model coefficients. | |
vtkSmartPointer< vtkDataSet > | createLine (const pcl::ModelCoefficients &coefficients) |
Create a line shape from a set of model coefficients. | |
template<typename P1 , typename P2 > | |
vtkSmartPointer< vtkDataSet > | createLine (const P1 &pt1, const P2 &pt2) |
Create a line shape from two points. | |
vtkSmartPointer< vtkDataSet > | createPlane (const pcl::ModelCoefficients &coefficients) |
Create a planar shape from a set of model coefficients. | |
template<typename PointT > | |
vtkSmartPointer< vtkDataSet > | createPolygon (const pcl::PointCloud< PointT > &cloud) |
Create a 3d poly line from a set of points. | |
vtkSmartPointer< vtkDataSet > | createSphere (const pcl::ModelCoefficients &coefficients, int res=10) |
Create a sphere shape from a set of model coefficients. | |
template<typename PointT > | |
vtkSmartPointer< vtkDataSet > | createSphere (const PointT ¢er, double radius, int res=10) |
Create a sphere shape from a point and a radius. | |
void | getCorrespondingPointCloud (vtkPolyData *src, const pcl::PointCloud< pcl::PointXYZ > &tgt, std::vector< int > &indices) |
Obtain a list of corresponding indices, for a set of vtk points, from a pcl::PointCloud. | |
void | getRandomColors (double &r, double &g, double &b, double min=0.2, double max=2.8) |
Get (good) random values for R/G/B. | |
bool | savePointData (vtkPolyData *data, const std::string &out_file, const boost::shared_ptr< CloudActorMap > &actors) |
Saves the vtk-formatted Point Cloud data into a set of files, based on whether the data comes from previously loaded PCD files. The PCD files are matched using the a list of names for the actors on screen. | |
vtkStandardNewMacro (PCLHistogramVisualizerInteractorStyle) | |
vtkStandardNewMacro (PCLVisualizerInteractorStyle) | |
vtkStandardNewMacro (PCLVisualizerInteractor) |
typedef std::map<std::string, CloudActor> pcl_visualization::CloudActorMap |
Definition at line 73 of file actor_map.h.
typedef std::map<std::string, RenWinInteract> pcl_visualization::RenWinInteractMap |
Definition at line 75 of file ren_win_interact_map.h.
typedef std::map<std::string, vtkSmartPointer<vtkProp> > pcl_visualization::ShapeActorMap |
Definition at line 75 of file actor_map.h.
vtkSmartPointer< vtkDataSet > pcl_visualization::create2DCircle | ( | const pcl::ModelCoefficients & | coefficients, | |
double | z = 0.0 | |||
) |
Create a 2d circle shape from a set of model coefficients.
coefficients | the model coefficients (x, y, radius) | |
z | (optional) specify a z value (default: 0) |
Definition at line 116 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createCone | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a cone shape from a set of model coefficients.
coefficients | the cone coefficients (point_on_axis, axis_direction, radius)) |
Definition at line 156 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createCylinder | ( | const pcl::ModelCoefficients & | coefficients, | |
int | numsides = 30 | |||
) |
Create a cylinder shape from a set of model coefficients.
coefficients | the model coefficients (point_on_axis, axis_direction, radius) | |
numsides | (optional) the number of sides used for rendering the cylinder |
Definition at line 45 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createLine | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a line shape from a set of model coefficients.
coefficients | the model coefficients (point_on_line, line_direction) |
Definition at line 87 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createLine | ( | const P1 & | pt1, | |
const P2 & | pt2 | |||
) | [inline] |
Create a line shape from two points.
pt1 | the first point on the line | |
pt2 | the end point on the line |
Definition at line 73 of file shapes.hpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createPlane | ( | const pcl::ModelCoefficients & | coefficients | ) |
Create a planar shape from a set of model coefficients.
coefficients | the model coefficients (a, b, c, d with ax+by+cz+d=0) |
Definition at line 103 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createPolygon | ( | const pcl::PointCloud< PointT > & | cloud | ) | [inline] |
Create a 3d poly line from a set of points.
cloud | the set of points used to create the 3d polyline |
Definition at line 43 of file shapes.hpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createSphere | ( | const pcl::ModelCoefficients & | coefficients, | |
int | res = 10 | |||
) |
Create a sphere shape from a set of model coefficients.
coefficients | the model coefficients (sphere center, radius) | |
res | (optional) the resolution used for rendering the model |
Definition at line 64 of file shapes.cpp.
vtkSmartPointer< vtkDataSet > pcl_visualization::createSphere | ( | const PointT & | center, | |
double | radius, | |||
int | res = 10 | |||
) | [inline] |
Create a sphere shape from a point and a radius.
center | the center of the sphere | |
radius | the radius of the sphere | |
res | (optional) the resolution used for rendering the model |
Definition at line 90 of file shapes.hpp.
void pcl_visualization::getCorrespondingPointCloud | ( | vtkPolyData * | src, | |
const pcl::PointCloud< pcl::PointXYZ > & | tgt, | |||
std::vector< int > & | indices | |||
) |
void pcl_visualization::getRandomColors | ( | double & | r, | |
double & | g, | |||
double & | b, | |||
double | min = 0.2 , |
|||
double | max = 2.8 | |||
) |
Get (good) random values for R/G/B.
r | the resultant R color value | |
g | the resultant G color value | |
b | the resultant B color value |
Definition at line 48 of file common.cpp.
bool pcl_visualization::savePointData | ( | vtkPolyData * | data, | |
const std::string & | out_file, | |||
const boost::shared_ptr< CloudActorMap > & | actors | |||
) |
Saves the vtk-formatted Point Cloud data into a set of files, based on whether the data comes from previously loaded PCD files. The PCD files are matched using the a list of names for the actors on screen.
data | the vtk data | |
out_file | the output file (extra indices will be appended to it) | |
actors | the list of actors present on screen |
pcl_visualization::vtkStandardNewMacro | ( | PCLHistogramVisualizerInteractorStyle | ) |
pcl_visualization::vtkStandardNewMacro | ( | PCLVisualizerInteractorStyle | ) |
pcl_visualization::vtkStandardNewMacro | ( | PCLVisualizerInteractor | ) |