pcl_visualization::PCLVisualizer Class Reference

PCL Visualizer main class. More...

#include <pcl_visualizer.h>

List of all members.

Classes

struct  ExitCallback
struct  ExitMainLoopTimerCallback

Public 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

Public Member Functions

bool addCircle (const pcl::ModelCoefficients &coefficients, const std::string &id="circle", int viewport=0)
 Add a circle from a set of given model coefficients.
bool addCone (const pcl::ModelCoefficients &coefficients, const std::string &id="cone", int viewport=0)
 Add a cone from a set of given model coefficients.
void addCoordinateSystem (double scale, float x, float y, float z, int viewport=0)
 Adds 3D axes describing a coordinate system to screen at x, y, z.
void addCoordinateSystem (double scale=1.0, int viewport=0)
 Adds 3D axes describing a coordinate system to screen at 0,0,0.
bool addCylinder (const pcl::ModelCoefficients &coefficients, const std::string &id="cylinder", int viewport=0)
 Add a cylinder from a set of given model coefficients.
bool addLine (const pcl::ModelCoefficients &coefficients, const std::string &id="line", int viewport=0)
 Add a line from a set of given model coefficients.
template<typename P1 , typename P2 >
bool addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id="line", int viewport=0)
 Add a line segment from two points.
template<typename P1 , typename P2 >
bool addLine (const P1 &pt1, const P2 &pt2, const std::string &id="line", int viewport=0)
 Add a line segment from two points.
bool addModelFromPLYFile (const std::string &filename, vtkSmartPointer< vtkTransform > transform, const std::string &id="PLYModel", int viewport=0)
 Add a PLYmodel as a mesh and applies given transformation.
bool addModelFromPLYFile (const std::string &filename, const std::string &id="PLYModel", int viewport=0)
 Add a PLYmodel as a mesh.
bool addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id="plane", int viewport=0)
 Add a plane from a set of given model coefficients.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const PointCloudColorHandler< PointT > &color_handler, const PointCloudGeometryHandler< PointT > &geometry_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const GeometryHandlerConstPtr &geometry_handler, const ColorHandlerConstPtr &color_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const ColorHandlerConstPtr &color_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const PointCloudColorHandler< PointT > &color_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const GeometryHandlerConstPtr &geometry_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const PointCloudGeometryHandler< PointT > &geometry_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const pcl::PointCloud< PointT > &cloud, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
bool addPointCloud (const pcl::PointCloud< pcl::PointXYZ > &cloud, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud to screen.
template<typename PointT , typename PointNT >
bool addPointCloudNormals (const pcl::PointCloud< PointT > &cloud, const pcl::PointCloud< PointNT > &normals, int level=100, double scale=0.02, const std::string &id="cloud", int viewport=0)
 Add the estimated surface normals of a Point Cloud to screen.
template<typename PointNT >
bool addPointCloudNormals (const pcl::PointCloud< PointNT > &cloud, int level=100, double scale=0.02, const std::string &id="cloud", int viewport=0)
 Add the estimated surface normals of a Point Cloud to screen.
bool addPointCloudPrincipalCurvatures (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointCloud< pcl::Normal > &normals, const pcl::PointCloud< pcl::PrincipalCurvatures > &pcs, int level=100, double scale=1.0, const std::string &id="cloud", int viewport=0)
 Add the estimated principal curvatures of a Point Cloud to screen.
template<typename PointT >
bool addPolygon (const pcl::PointCloud< PointT > &cloud, const std::string &id="polygon", int viewport=0)
 Add a polygon (polyline) that represents the input point cloud (connects all points in order).
template<typename PointT >
bool addPolygon (const pcl::PointCloud< PointT > &cloud, double r, double g, double b, const std::string &id="polygon", int viewport=0)
 Add a polygon (polyline) that represents the input point cloud (connects all points in order).
bool addSphere (const pcl::ModelCoefficients &coefficients, const std::string &id="sphere", int viewport=0)
 Add a sphere from a set of given model coefficients.
template<typename PointT >
bool addSphere (const PointT &center, double radius, double r, double g, double b, const std::string &id="sphere", int viewport=0)
 Add a sphere shape from a point and a radius.
template<typename PointT >
bool addSphere (const PointT &center, double radius, const std::string &id="sphere", int viewport=0)
 Add a line segment from two points to a group of lines. If the group doesn't exist, it will get created.
bool addText (const std::string &text, int xpos, int ypos, int r, int g, int b, const std::string &id="", int viewport=0)
 Add a text to screen.
bool addText (const std::string &text, int xpos, int ypos, const std::string &id="", int viewport=0)
 Add a text to screen.
void createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport)
 Create a new viewport from [xmin,ymin] -> [xmax,ymax].
bool getCameraParameters (int argc, char **argv)
 Search for camera parameters at the command line and set them internally.
int getColorHandlerIndex (const std::string &id)
 Get the color handler index of a rendered PointCloud based on its ID.
int getGeometryHandlerIndex (const std::string &id)
 Get the geometry handler index of a rendered PointCloud based on its ID.
bool getPointCloudRenderingProperties (int property, double &value, const std::string &id="cloud")
 Get the rendering properties of a PointCloud.
void initCameraParameters ()
 Initialize camera parameters with some default values.
 PCLVisualizer (int &argc, char **argv, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New())
 PCL Visualizer constructor.
 PCLVisualizer (const std::string &name="")
 PCL Visualizer constructor.
void removeCoordinateSystem (int viewport=0)
 Removes a previously added 3D axes (coordinate system).
bool removePointCloud (const std::string &id="cloud", int viewport=0)
 Removes a Point Cloud from screen, based on a given ID.
bool removeShape (const std::string &id="cloud", int viewport=0)
 Removes an added shape from screen (line, polygon, etc.), based on a given ID.
void resetCamera ()
 Reset camera parameters and render.
void resetStoppedFlag ()
 Set the stopped flag back to false.
void setBackgroundColor (const double &r, const double &g, const double &b, int viewport=0)
 Set the viewport's background color.
bool setPointCloudRenderingProperties (int property, double value, const std::string &id="cloud", int viewport=0)
 Set the rendering properties of a PointCloud.
bool setPointCloudRenderingProperties (int property, double val1, double val2, double val3, const std::string &id="cloud", int viewport=0)
 Set the rendering properties of a PointCloud (3x values - e.g., RGB).
bool setShapeRenderingProperties (int property, double value, const std::string &id, int viewport=0)
 Set the rendering properties of a shape.
void spin ()
 Spin method. Calls the interactor and runs an internal loop.
void spinOnce (int time=1, bool force_redraw=false)
 Spin once method. Calls the interactor and updates the screen once.
void updateCamera ()
 Update camera parameters and render.
bool updateColorHandlerIndex (const std::string &id, int index)
 Update/set the color index of a renderered PointCloud based on its ID.
bool wasStopped () const
 Returns true when the user tried to close the window.
virtual ~PCLVisualizer ()
 PCL Visualizer destructor.

Public Attributes

Camera camera_
 Camera view, window position and size.

Protected Attributes

vtkSmartPointer
< PCLVisualizerInteractor
interactor_
 The render window interactor.

Private Member Functions

void addActorToRenderer (const vtkSmartPointer< vtkProp > &actor, int viewport=0)
 Internal method. Adds a vtk actor to screen.
void convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, vtkSmartPointer< vtkPolyData > &polydata)
 Converts a PCL templated PointCloud object to a vtk polydata object.
template<typename PointT >
void convertPointCloudToVTKPolyData (const PointCloudGeometryHandler< PointT > &geometry_handler, vtkSmartPointer< vtkPolyData > &polydata)
 Converts a PCL templated PointCloud object to a vtk polydata object.
template<typename PointT >
void convertPointCloudToVTKPolyData (const pcl::PointCloud< PointT > &cloud, vtkSmartPointer< vtkPolyData > &polydata)
 Converts a PCL templated PointCloud object to a vtk polydata object.
void convertPointCloudToVTKPolyData (const pcl::PointCloud< pcl::PointXYZ > &cloud, vtkSmartPointer< vtkPolyData > &polydata)
 Converts a PCL templated PointCloud object to a vtk polydata object.
void createActorFromVTKDataSet (const vtkSmartPointer< vtkDataSet > &data, vtkSmartPointer< vtkLODActor > &actor)
 Internal method. Creates a vtk actor from a vtk polydata object.
void removeActorFromRenderer (const vtkSmartPointer< vtkProp > &actor, int viewport=0)
 Internal method. Adds a vtk actor to screen.
void removeActorFromRenderer (const vtkSmartPointer< vtkLODActor > &actor, int viewport=0)
 Internal method. Removes a vtk actor from the screen.

Private Attributes

CloudActorMap cloud_actor_map_
 Internal list with actor pointers and name IDs for point clouds.
vtkSmartPointer< ExitCallbackexit_callback_
vtkSmartPointer
< ExitMainLoopTimerCallback
exit_main_loop_timer_callback_
 Callback object enabling us to leave the main loop, when a timer fires.
vtkSmartPointer
< vtkRendererCollection > 
rens_
 The collection of renderers used.
ShapeActorMap shape_actor_map_
 Internal list with actor pointers and name IDs for shapes.
vtkSmartPointer
< PCLVisualizerInteractorStyle
style_
 The render window interactor style.
vtkSmartPointer< vtkRenderWindow > win_
 The render window.

Detailed Description

PCL Visualizer main class.

Author:
Radu Bogdan Rusu

Definition at line 70 of file pcl_visualizer.h.


Member Typedef Documentation

Definition at line 77 of file pcl_visualizer.h.

Definition at line 79 of file pcl_visualizer.h.

Definition at line 78 of file pcl_visualizer.h.

Definition at line 73 of file pcl_visualizer.h.

Definition at line 75 of file pcl_visualizer.h.

Definition at line 74 of file pcl_visualizer.h.


Constructor & Destructor Documentation

pcl_visualization::PCLVisualizer::PCLVisualizer ( const std::string &  name = ""  ) 

PCL Visualizer constructor.

Parameters:
name the window name (empty by default)

Definition at line 46 of file pcl_visualizer.cpp.

pcl_visualization::PCLVisualizer::PCLVisualizer ( int &  argc,
char **  argv,
const std::string &  name = "",
PCLVisualizerInteractorStyle style = PCLVisualizerInteractorStyle::New () 
)

PCL Visualizer constructor.

Parameters:
argc 
argv 
name the window name (empty by default)
interactor style (defaults to PCLVisualizerInteractorStyle)

Definition at line 108 of file pcl_visualizer.cpp.

pcl_visualization::PCLVisualizer::~PCLVisualizer (  )  [virtual]

PCL Visualizer destructor.

Definition at line 181 of file pcl_visualizer.cpp.


Member Function Documentation

void pcl_visualization::PCLVisualizer::addActorToRenderer ( const vtkSmartPointer< vtkProp > &  actor,
int  viewport = 0 
) [private]

Internal method. Adds a vtk actor to screen.

Parameters:
actor a pointer to the vtk actor object
viewport the view port where the actor should be added to (default: all)

Definition at line 552 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addCircle ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "circle",
int  viewport = 0 
)

Add a circle from a set of given model coefficients.

Parameters:
coefficients the model coefficients (x, y, radius)
id the circle id/name (default: "circle")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1190 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addCone ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "cone",
int  viewport = 0 
)

Add a cone from a set of given model coefficients.

Parameters:
coefficients the model coefficients (point_on_axis, axis_direction, radiu)
id the cone id/name (default: "cone")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1215 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::addCoordinateSystem ( double  scale,
float  x,
float  y,
float  z,
int  viewport = 0 
)

Adds 3D axes describing a coordinate system to screen at x, y, z.

Parameters:
scale the scale of the axes (default: 1)
x the X position of the axes
y the Y position of the axes
z the Z position of the axes
viewport the view port where the 3D axes should be added (default: all)

Definition at line 261 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::addCoordinateSystem ( double  scale = 1.0,
int  viewport = 0 
)

Adds 3D axes describing a coordinate system to screen at 0,0,0.

Parameters:
scale the scale of the axes (default: 1)
viewport the view port where the 3D axes should be added (default: all)

Definition at line 225 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addCylinder ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "cylinder",
int  viewport = 0 
)

Add a cylinder from a set of given model coefficients.

Parameters:
coefficients the model coefficients (point_on_axis, axis_direction, radius)
id the cylinder id/name (default: "cylinder")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1024 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addLine ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "line",
int  viewport = 0 
)

Add a line from a set of given model coefficients.

Parameters:
coefficients the model coefficients (point_on_line, direction)
id the line id/name (default: "line")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1135 of file pcl_visualizer.cpp.

template<typename P1 , typename P2 >
bool pcl_visualization::PCLVisualizer::addLine ( const P1 &  pt1,
const P2 &  pt2,
double  r,
double  g,
double  b,
const std::string &  id = "line",
int  viewport = 0 
) [inline]

Add a line segment from two points.

Parameters:
pt1 the first (start) point on the line
pt2 the second (end) point on the line
r the red channel of the color that the line should be rendered with
g the green channel of the color that the line should be rendered with
b the blue channel of the color that the line should be rendered with
id the line id/name (default: "line")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 540 of file pcl_visualizer.hpp.

template<typename P1 , typename P2 >
bool pcl_visualization::PCLVisualizer::addLine ( const P1 &  pt1,
const P2 &  pt2,
const std::string &  id = "line",
int  viewport = 0 
) [inline]

Add a line segment from two points.

Parameters:
pt1 the first (start) point on the line
pt2 the second (end) point on the line
id the line id/name (default: "line")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 515 of file pcl_visualizer.hpp.

bool pcl_visualization::PCLVisualizer::addModelFromPLYFile ( const std::string &  filename,
vtkSmartPointer< vtkTransform >  transform,
const std::string &  id = "PLYModel",
int  viewport = 0 
)

Add a PLYmodel as a mesh and applies given transformation.

Parameters:
filename of the ply file
transform transformation to apply
id the model id/name (default: "PLYModel")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1101 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addModelFromPLYFile ( const std::string &  filename,
const std::string &  id = "PLYModel",
int  viewport = 0 
)

Add a PLYmodel as a mesh.

Parameters:
filename of the ply file
id the model id/name (default: "PLYModel")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1074 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addPlane ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "plane",
int  viewport = 0 
)

Add a plane from a set of given model coefficients.

Parameters:
coefficients the model coefficients (a, b, c, d with ax+by+cz+d=0)
id the plane id/name (default: "plane")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1165 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const PointCloudColorHandler< PointT > &  color_handler,
const PointCloudGeometryHandler< PointT > &  geometry_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
color_handler a specific PointCloud visualizer handler for colors
geometry_handler use a geometry handler object to extract the XYZ data
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 368 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const GeometryHandlerConstPtr geometry_handler,
const ColorHandlerConstPtr color_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
geometry_handler a specific PointCloud visualizer handler for geometry
color_handler a specific PointCloud visualizer handler for colors
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 306 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const ColorHandlerConstPtr color_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
color_handler a specific PointCloud visualizer handler for colors
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 246 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const PointCloudColorHandler< PointT > &  color_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
color_handler a specific PointCloud visualizer handler for colors
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 187 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const GeometryHandlerConstPtr geometry_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
geometry_handler use a geometry handler object to extract the XYZ data
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 136 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const PointCloudGeometryHandler< PointT > &  geometry_handler,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
geometry_handler use a geometry handler object to extract the XYZ data
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 88 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< PointT > &  cloud,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add a Point Cloud (templated) to screen.

Parameters:
cloud the input point cloud dataset
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 40 of file pcl_visualizer.hpp.

bool pcl_visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< pcl::PointXYZ > &  cloud,
const std::string &  id = "cloud",
int  viewport = 0 
)

Add a Point Cloud to screen.

Parameters:
cloud the input point cloud dataset
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 485 of file pcl_visualizer.cpp.

template<typename PointT , typename PointNT >
bool pcl_visualization::PCLVisualizer::addPointCloudNormals ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
int  level = 100,
double  scale = 0.02,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add the estimated surface normals of a Point Cloud to screen.

Parameters:
cloud the input point cloud dataset containing the XYZ data
normals the input point cloud dataset containing the normal data
level display only every level'th point (default: 100)
scale the normal arrow scale (default: 0.02m)
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 645 of file pcl_visualizer.hpp.

template<typename PointNT >
bool pcl_visualization::PCLVisualizer::addPointCloudNormals ( const pcl::PointCloud< PointNT > &  cloud,
int  level = 100,
double  scale = 0.02,
const std::string &  id = "cloud",
int  viewport = 0 
) [inline]

Add the estimated surface normals of a Point Cloud to screen.

Parameters:
cloud the input point cloud dataset containing XYZ data and normals
level display only every level'th point (default: 100)
scale the normal arrow scale (default: 0.02m)
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 637 of file pcl_visualizer.hpp.

bool pcl_visualization::PCLVisualizer::addPointCloudPrincipalCurvatures ( const pcl::PointCloud< pcl::PointXYZ > &  cloud,
const pcl::PointCloud< pcl::Normal > &  normals,
const pcl::PointCloud< pcl::PrincipalCurvatures > &  pcs,
int  level = 100,
double  scale = 1.0,
const std::string &  id = "cloud",
int  viewport = 0 
)

Add the estimated principal curvatures of a Point Cloud to screen.

Parameters:
cloud the input point cloud dataset containing the XYZ data
normals the input point cloud dataset containing the normal data
pcs the input point cloud dataset containing the principal curvatures data
level display only every level'th point (default: 100)
scale the normal arrow scale (default: 1.0))
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud should be added (default: all)

Definition at line 384 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPolygon ( const pcl::PointCloud< PointT > &  cloud,
const std::string &  id = "polygon",
int  viewport = 0 
) [inline]

Add a polygon (polyline) that represents the input point cloud (connects all points in order).

Parameters:
cloud the point cloud dataset representing the polygon
id the polygon id/name (default: "polygon")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 476 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addPolygon ( const pcl::PointCloud< PointT > &  cloud,
double  r,
double  g,
double  b,
const std::string &  id = "polygon",
int  viewport = 0 
) [inline]

Add a polygon (polyline) that represents the input point cloud (connects all points in order).

Parameters:
cloud the point cloud dataset representing the polygon
r the red channel of the color that the polygon should be rendered with
g the green channel of the color that the polygon should be rendered with
b the blue channel of the color that the polygon should be rendered with
id (optional) the polygon id/name (default: "polygon")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 501 of file pcl_visualizer.hpp.

bool pcl_visualization::PCLVisualizer::addSphere ( const pcl::ModelCoefficients &  coefficients,
const std::string &  id = "sphere",
int  viewport = 0 
)

Add a sphere from a set of given model coefficients.

Parameters:
coefficients the model coefficients (sphere center, radius)
id the sphere id/name (default: "sphere")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 1049 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addSphere ( const PointT &  center,
double  radius,
double  r,
double  g,
double  b,
const std::string &  id = "sphere",
int  viewport = 0 
) [inline]

Add a sphere shape from a point and a radius.

Parameters:
center the center of the sphere
radius the radius of the sphere
r the red channel of the color that the sphere should be rendered with
g the green channel of the color that the sphere should be rendered with
b the blue channel of the color that the sphere should be rendered with
id the line id/name (default: "sphere")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 624 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl_visualization::PCLVisualizer::addSphere ( const PointT &  center,
double  radius,
const std::string &  id = "sphere",
int  viewport = 0 
) [inline]

Add a line segment from two points to a group of lines. If the group doesn't exist, it will get created.

Parameters:
pt1 the first (start) point on the line
pt2 the second (end) point on the line
group_id the line group id/name (default: "line_group")
viewport (optional) the id of the new viewport (default: 0) Add a sphere shape from a point and a radius
center the center of the sphere
radius the radius of the sphere
id the line id/name (default: "sphere")
viewport (optional) the id of the new viewport (default: 0)

Definition at line 599 of file pcl_visualizer.hpp.

bool pcl_visualization::PCLVisualizer::addText ( const std::string &  text,
int  xpos,
int  ypos,
int  r,
int  g,
int  b,
const std::string &  id = "",
int  viewport = 0 
)

Add a text to screen.

Parameters:
text the text to add
xpos the X position on screen where the text should be added
ypos the Y position on screen where the text should be added
r the red color value
g the green color value
b the blue color vlaue
id the text object id (default: equal to the "text" parameter)
viewport the view port (default: all)

Definition at line 1300 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::addText ( const std::string &  text,
int  xpos,
int  ypos,
const std::string &  id = "",
int  viewport = 0 
)

Add a text to screen.

Parameters:
text the text to add
xpos the X position on screen where the text should be added
ypos the Y position on screen where the text should be added
id the text object id (default: equal to the "text" parameter)
viewport the view port (default: all)

Definition at line 1264 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const GeometryHandlerConstPtr geometry_handler,
vtkSmartPointer< vtkPolyData > &  polydata 
) [private]

Converts a PCL templated PointCloud object to a vtk polydata object.

Parameters:
geometry_handler the geometry handler object used to extract the XYZ data
polydata the resultant polydata containing the cloud

Definition at line 658 of file pcl_visualizer.cpp.

template<typename PointT >
void pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const PointCloudGeometryHandler< PointT > &  geometry_handler,
vtkSmartPointer< vtkPolyData > &  polydata 
) [inline, private]

Converts a PCL templated PointCloud object to a vtk polydata object.

Parameters:
geometry_handler the geometry handler object used to extract the XYZ data
polydata the resultant polydata containing the cloud

Definition at line 455 of file pcl_visualizer.hpp.

template<typename PointT >
void pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const pcl::PointCloud< PointT > &  cloud,
vtkSmartPointer< vtkPolyData > &  polydata 
) [inline, private]

Converts a PCL templated PointCloud object to a vtk polydata object.

Parameters:
cloud the input PCL PointCloud dataset
polydata the resultant polydata containing the cloud

Definition at line 427 of file pcl_visualizer.hpp.

void pcl_visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const pcl::PointCloud< pcl::PointXYZ > &  cloud,
vtkSmartPointer< vtkPolyData > &  polydata 
) [private]

Converts a PCL templated PointCloud object to a vtk polydata object.

Parameters:
cloud the input PCL PointCloud dataset
polydata the resultant polydata containing the cloud

Definition at line 629 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::createActorFromVTKDataSet ( const vtkSmartPointer< vtkDataSet > &  data,
vtkSmartPointer< vtkLODActor > &  actor 
) [private]

Internal method. Creates a vtk actor from a vtk polydata object.

Parameters:
data the vtk polydata object to create an actor for
actor the resultant vtk actor object

Definition at line 602 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::createViewPort ( double  xmin,
double  ymin,
double  xmax,
double  ymax,
int &  viewport 
)

Create a new viewport from [xmin,ymin] -> [xmax,ymax].

Parameters:
xmin the minimum X coordinate for the viewport (0.0 <= 1.0)
ymin the minimum Y coordinate for the viewport (0.0 <= 1.0)
xmax the maximum X coordinate for the viewport (0.0 <= 1.0)
ymax the maximum Y coordinate for the viewport (0.0 <= 1.0)
viewport the id of the new viewport

Definition at line 1240 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::getCameraParameters ( int  argc,
char **  argv 
)

Search for camera parameters at the command line and set them internally.

Parameters:
argc 
argv 

Definition at line 906 of file pcl_visualizer.cpp.

int pcl_visualization::PCLVisualizer::getColorHandlerIndex ( const std::string &  id  )  [inline]

Get the color handler index of a rendered PointCloud based on its ID.

Parameters:
id the point cloud object id

Definition at line 295 of file pcl_visualizer.h.

int pcl_visualization::PCLVisualizer::getGeometryHandlerIndex ( const std::string &  id  )  [inline]

Get the geometry handler index of a rendered PointCloud based on its ID.

Parameters:
id the point cloud object id

Definition at line 306 of file pcl_visualizer.h.

bool pcl_visualization::PCLVisualizer::getPointCloudRenderingProperties ( int  property,
double &  value,
const std::string &  id = "cloud" 
)

Get the rendering properties of a PointCloud.

Parameters:
property the property type
value the resultant property value
id the point cloud object id (default: cloud)

Definition at line 735 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::initCameraParameters (  ) 

Initialize camera parameters with some default values.

Definition at line 867 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::removeActorFromRenderer ( const vtkSmartPointer< vtkProp > &  actor,
int  viewport = 0 
) [private]

Internal method. Adds a vtk actor to screen.

Parameters:
actor a pointer to the vtk actor object
viewport the view port where the actor should be added to (default: all)

Definition at line 577 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::removeActorFromRenderer ( const vtkSmartPointer< vtkLODActor > &  actor,
int  viewport = 0 
) [private]

Internal method. Removes a vtk actor from the screen.

Parameters:
actor a pointer to the vtk actor object
viewport the view port where the actor should be removed from (default: all)

Definition at line 527 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::removeCoordinateSystem ( int  viewport = 0  ) 

Removes a previously added 3D axes (coordinate system).

Parameters:
viewport the view port where the 3D axes should be removed from (default: all)

Definition at line 298 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::removePointCloud ( const std::string &  id = "cloud",
int  viewport = 0 
)

Removes a Point Cloud from screen, based on a given ID.

Parameters:
id the point cloud object id (i.e., given on addPointCloud)
viewport the view port from where the Point Cloud should be removed (default: all)

Definition at line 334 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::removeShape ( const std::string &  id = "cloud",
int  viewport = 0 
)

Removes an added shape from screen (line, polygon, etc.), based on a given ID.

Parameters:
id the shape object id (i.e., given on addLine etc.)
viewport the view port from where the Point Cloud should be removed (default: all)

Definition at line 363 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::resetCamera (  ) 

Reset camera parameters and render.

Definition at line 893 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::resetStoppedFlag (  )  [inline]

Set the stopped flag back to false.

Definition at line 357 of file pcl_visualizer.h.

void pcl_visualization::PCLVisualizer::setBackgroundColor ( const double &  r,
const double &  g,
const double &  b,
int  viewport = 0 
)

Set the viewport's background color.

Parameters:
r the red component of the RGB color
g the green component of the RGB color
b the blue component of the RGB color
viewport the view port (default: all)

Definition at line 679 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::setPointCloudRenderingProperties ( int  property,
double  value,
const std::string &  id = "cloud",
int  viewport = 0 
)

Set the rendering properties of a PointCloud.

Parameters:
property the property type
value the value to be set
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud's rendering properties should be modified (default: all)

Definition at line 776 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::setPointCloudRenderingProperties ( int  property,
double  val1,
double  val2,
double  val3,
const std::string &  id = "cloud",
int  viewport = 0 
)

Set the rendering properties of a PointCloud (3x values - e.g., RGB).

Parameters:
property the property type
val1 the first value to be set
val2 the second value to be set
val2 the third value to be set
id the point cloud object id (default: cloud)
viewport the view port where the Point Cloud's rendering properties should be modified (default: all)

Definition at line 703 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::setShapeRenderingProperties ( int  property,
double  value,
const std::string &  id,
int  viewport = 0 
)

Set the rendering properties of a shape.

Parameters:
property the property type
value the value to be set
id the shape object id
viewport the view port where the shape's properties should be modified (default: all)

Definition at line 820 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::spin (  ) 

Spin method. Calls the interactor and runs an internal loop.

Definition at line 189 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::spinOnce ( int  time = 1,
bool  force_redraw = false 
)

Spin once method. Calls the interactor and updates the screen once.

Parameters:
time - How long (in ms) should the visualization loop be allowed to run.
force_redraw - if false it might return without doing anything if the interactor's framerate does not require a redraw yet.

Definition at line 199 of file pcl_visualizer.cpp.

void pcl_visualization::PCLVisualizer::updateCamera (  ) 

Update camera parameters and render.

Definition at line 878 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::updateColorHandlerIndex ( const std::string &  id,
int  index 
)

Update/set the color index of a renderered PointCloud based on its ID.

Parameters:
id the point cloud object id
index the color handler index to use

Definition at line 1336 of file pcl_visualizer.cpp.

bool pcl_visualization::PCLVisualizer::wasStopped (  )  const [inline]

Returns true when the user tried to close the window.

Definition at line 355 of file pcl_visualizer.h.


Member Data Documentation

Camera view, window position and size.

Definition at line 489 of file pcl_visualizer.h.

Internal list with actor pointers and name IDs for point clouds.

Definition at line 561 of file pcl_visualizer.h.

Definition at line 550 of file pcl_visualizer.h.

Callback object enabling us to leave the main loop, when a timer fires.

Definition at line 549 of file pcl_visualizer.h.

The render window interactor.

Definition at line 508 of file pcl_visualizer.h.

vtkSmartPointer<vtkRendererCollection> pcl_visualization::PCLVisualizer::rens_ [private]

The collection of renderers used.

Definition at line 553 of file pcl_visualizer.h.

Internal list with actor pointers and name IDs for shapes.

Definition at line 564 of file pcl_visualizer.h.

The render window interactor style.

Definition at line 558 of file pcl_visualizer.h.

vtkSmartPointer<vtkRenderWindow> pcl_visualization::PCLVisualizer::win_ [private]

The render window.

Definition at line 555 of file pcl_visualizer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pcl_visualization
Author(s): Radu Bogdan Rusu, Bastian Steder, Ethan Rublee
autogenerated on Fri Jan 11 09:59:19 2013