Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl::visualization::PCLVisualizer Class Reference

PCL Visualizer main class. More...

#include <pcl_visualizer.h>

List of all members.

Classes

struct  ExitCallback
struct  ExitMainLoopTimerCallback
struct  FPSCallback

Public Types

typedef PointCloudColorHandler
< pcl::PCLPointCloud2
ColorHandler
typedef ColorHandler::ConstPtr ColorHandlerConstPtr
typedef ColorHandler::Ptr ColorHandlerPtr
typedef boost::shared_ptr
< const PCLVisualizer
ConstPtr
typedef
PointCloudGeometryHandler
< pcl::PCLPointCloud2
GeometryHandler
typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr
typedef GeometryHandler::Ptr GeometryHandlerPtr
typedef boost::shared_ptr
< PCLVisualizer
Ptr

Public Member Functions

template<typename P1 , typename P2 >
bool addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, const std::string &id="arrow", int viewport=0)
 Add a line arrow segment between two points, and display the distance between them.
template<typename P1 , typename P2 >
bool addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length, const std::string &id="arrow", int viewport=0)
 Add a line arrow segment between two points, and display the distance between them.
template<typename P1 , typename P2 >
bool addArrow (const P1 &pt1, const P2 &pt2, double r_line, double g_line, double b_line, double r_text, double g_text, double b_text, const std::string &id="arrow", int viewport=0)
 Add a line arrow segment between two points, and display the distance between them in a given color.
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=1.0, int viewport=0)
 Adds 3D axes describing a coordinate system to screen at 0,0,0.
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, const Eigen::Affine3f &t, int viewport=0)
 Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw.
template<typename PointT >
bool addCorrespondences (const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const std::vector< int > &correspondences, const std::string &id="correspondences", int viewport=0)
 Add the specified correspondences to the display.
template<typename PointT >
bool addCorrespondences (const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const pcl::Correspondences &correspondences, int nth, const std::string &id="correspondences", int viewport=0)
 Add the specified correspondences to the display.
template<typename PointT >
bool addCorrespondences (const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const pcl::Correspondences &correspondences, const std::string &id="correspondences", int viewport=0)
 Add the specified correspondences to the display.
bool addCube (const pcl::ModelCoefficients &coefficients, const std::string &id="cube", int viewport=0)
 Add a cube from a set of given model coefficients.
bool addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation, double width, double height, double depth, const std::string &id="cube", int viewport=0)
 Add a cube from a set of given model coefficients.
bool addCube (float x_min, float x_max, float y_min, float y_max, float z_min, float z_max, double r=1.0, double g=1.0, double b=1.0, const std::string &id="cube", int viewport=0)
 Add a cube.
bool addCylinder (const pcl::ModelCoefficients &coefficients, const std::string &id="cylinder", int viewport=0)
 Add a cylinder from a set of given model coefficients.
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.
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.
bool addLine (const pcl::ModelCoefficients &coefficients, const std::string &id="line", int viewport=0)
 Add a line from a set of given model coefficients.
bool addModelFromPLYFile (const std::string &filename, const std::string &id="PLYModel", int viewport=0)
 Add a PLYmodel as a mesh.
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 addModelFromPolyData (vtkSmartPointer< vtkPolyData > polydata, const std::string &id="PolyData", int viewport=0)
 Add a vtkPolydata as a mesh.
bool addModelFromPolyData (vtkSmartPointer< vtkPolyData > polydata, vtkSmartPointer< vtkTransform > transform, const std::string &id="PolyData", int viewport=0)
 Add a vtkPolydata as a mesh.
void addOrientationMarkerWidgetAxes (vtkRenderWindowInteractor *interactor)
 Adds a widget which shows an interactive axes display for orientation.
bool addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id="plane", int viewport=0)
 Add a plane from a set of given model coefficients.
bool addPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z, const std::string &id="plane", int viewport=0)
template<typename PointT >
bool addPointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
template<typename PointT >
bool addPointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &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 typename pcl::PointCloud< PointT >::ConstPtr &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 typename pcl::PointCloud< PointT >::ConstPtr &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 typename pcl::PointCloud< PointT >::ConstPtr &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 typename pcl::PointCloud< PointT >::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const ColorHandlerConstPtr &color_handler, const std::string &id="cloud", int viewport=0)
 Add a Point Cloud (templated) to screen.
bool addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const ColorHandlerConstPtr &color_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
 Add a binary blob Point Cloud to screen.
bool addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
 Add a binary blob Point Cloud to screen.
bool addPointCloud (const pcl::PCLPointCloud2::ConstPtr &cloud, const ColorHandlerConstPtr &color_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
 Add a binary blob Point Cloud to screen.
template<typename PointT >
bool addPointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &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.
bool addPointCloud (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
 Add a PointXYZ Point Cloud to screen.
bool addPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
 Add a PointXYZRGB Point Cloud to screen.
bool addPointCloud (const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
 Add a PointXYZRGBA Point Cloud to screen.
template<typename PointT , typename GradientT >
bool addPointCloudIntensityGradients (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const typename pcl::PointCloud< GradientT >::ConstPtr &gradients, int level=100, double scale=1e-6, const std::string &id="cloud", int viewport=0)
 Add the estimated surface intensity gradients of a Point Cloud to screen.
template<typename PointNT >
bool addPointCloudNormals (const typename pcl::PointCloud< PointNT >::ConstPtr &cloud, int level=100, float scale=0.02f, const std::string &id="cloud", int viewport=0)
 Add the estimated surface normals of a Point Cloud to screen.
template<typename PointT , typename PointNT >
bool addPointCloudNormals (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const typename pcl::PointCloud< PointNT >::ConstPtr &normals, int level=100, float scale=0.02f, 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 >::ConstPtr &cloud, const pcl::PointCloud< pcl::Normal >::ConstPtr &normals, const pcl::PointCloud< pcl::PrincipalCurvatures >::ConstPtr &pcs, int level=100, float scale=1.0f, 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 typename pcl::PointCloud< PointT >::ConstPtr &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)
template<typename PointT >
bool addPolygon (const typename pcl::PointCloud< PointT >::ConstPtr &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::PlanarPolygon< PointT > &polygon, double r, double g, double b, const std::string &id="polygon", int viewport=0)
 Add a planar polygon that represents the input point cloud (connects all points in order)
bool addPolygonMesh (const pcl::PolygonMesh &polymesh, const std::string &id="polygon", int viewport=0)
 Add a PolygonMesh object to screen.
template<typename PointT >
bool addPolygonMesh (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::vector< pcl::Vertices > &vertices, const std::string &id="polygon", int viewport=0)
 Add a PolygonMesh object to screen.
bool addPolylineFromPolygonMesh (const pcl::PolygonMesh &polymesh, const std::string &id="polyline", int viewport=0)
 Add a Polygonline from a polygonMesh object to screen.
template<typename PointT >
bool addSphere (const PointT &center, double radius, 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, double r, double g, double b, const std::string &id="sphere", int viewport=0)
 Add a sphere shape from a point and a radius.
bool addSphere (const pcl::ModelCoefficients &coefficients, const std::string &id="sphere", int viewport=0)
 Add a sphere from a set of given model coefficients.
bool addText (const std::string &text, int xpos, int ypos, const std::string &id="", int viewport=0)
 Add a text to screen.
bool addText (const std::string &text, int xpos, int ypos, double r, double g, double b, const std::string &id="", int viewport=0)
 Add a text to screen.
bool addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, const std::string &id="", int viewport=0)
 Add a text to screen.
template<typename PointT >
bool addText3D (const std::string &text, const PointT &position, double textScale=1.0, double r=1.0, double g=1.0, double b=1.0, const std::string &id="", int viewport=0)
 Add a 3d text to the scene.
bool cameraParamsSet () const
 Checks whether the camera parameters were manually loaded from file.
void close ()
 Stop the interaction and close the visualizaton window.
void createInteractor ()
 Create the internal Interactor object.
void createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport)
 Create a new viewport from [xmin,ymin] -> [xmax,ymax].
void createViewPortCamera (const int viewport)
 Create a new separate camera for the given viewport.
bool getCameraParameters (int argc, char **argv)
 Search for camera parameters at the command line and set them internally.
void getCameras (std::vector< Camera > &cameras)
 Get the current camera parameters.
CloudActorMapPtr getCloudActorMap ()
 Return a pointer to the CloudActorMap this visualizer uses.
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.
vtkSmartPointer
< PCLVisualizerInteractorStyle
getInteractorStyle ()
 Get a pointer to the current interactor style used.
bool getPointCloudRenderingProperties (int property, double &value, const std::string &id="cloud")
 Get the rendering properties of a PointCloud.
vtkSmartPointer
< vtkRendererCollection > 
getRendererCollection ()
 Return a pointer to the underlying VTK Renderer Collection.
vtkSmartPointer< vtkRenderWindow > getRenderWindow ()
 Return a pointer to the underlying VTK Render Window used.
Eigen::Affine3f getViewerPose (int viewport=0)
 Get the current viewing pose.
void initCameraParameters ()
 Initialize camera parameters with some default values.
 PCLVisualizer (const std::string &name="", const bool create_interactor=true)
 PCL Visualizer constructor.
 PCLVisualizer (int &argc, char **argv, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New(), const bool create_interactor=true)
 PCL Visualizer constructor.
boost::signals2::connection registerAreaPickingCallback (boost::function< void(const pcl::visualization::AreaPickingEvent &)> cb)
 Register a callback function for area picking events.
boost::signals2::connection registerAreaPickingCallback (void(*callback)(const pcl::visualization::AreaPickingEvent &, void *), void *cookie=NULL)
 Register a callback function for area picking events.
template<typename T >
boost::signals2::connection registerAreaPickingCallback (void(T::*callback)(const pcl::visualization::AreaPickingEvent &, void *), T &instance, void *cookie=NULL)
 Register a callback function for area picking events.
boost::signals2::connection registerKeyboardCallback (boost::function< void(const pcl::visualization::KeyboardEvent &)> cb)
 Register a callback boost::function for keyboard events.
boost::signals2::connection registerKeyboardCallback (void(*callback)(const pcl::visualization::KeyboardEvent &, void *), void *cookie=NULL)
 Register a callback function for keyboard events.
template<typename T >
boost::signals2::connection registerKeyboardCallback (void(T::*callback)(const pcl::visualization::KeyboardEvent &, void *), T &instance, void *cookie=NULL)
 Register a callback function for keyboard events.
boost::signals2::connection registerMouseCallback (boost::function< void(const pcl::visualization::MouseEvent &)> cb)
 Register a callback function for mouse events.
boost::signals2::connection registerMouseCallback (void(*callback)(const pcl::visualization::MouseEvent &, void *), void *cookie=NULL)
 Register a callback function for mouse events.
template<typename T >
boost::signals2::connection registerMouseCallback (void(T::*callback)(const pcl::visualization::MouseEvent &, void *), T &instance, void *cookie=NULL)
 Register a callback function for mouse events.
boost::signals2::connection registerPointPickingCallback (boost::function< void(const pcl::visualization::PointPickingEvent &)> cb)
 Register a callback function for point picking events.
boost::signals2::connection registerPointPickingCallback (void(*callback)(const pcl::visualization::PointPickingEvent &, void *), void *cookie=NULL)
 Register a callback function for point picking events.
template<typename T >
boost::signals2::connection registerPointPickingCallback (void(T::*callback)(const pcl::visualization::PointPickingEvent &, void *), T &instance, void *cookie=NULL)
 Register a callback function for point picking events.
bool removeAllPointClouds (int viewport=0)
 Remove all point cloud data on screen from the given viewport.
bool removeAllShapes (int viewport=0)
 Remove all 3D shape data on screen from the given viewport.
bool removeCoordinateSystem (int viewport=0)
 Removes a previously added 3D axes (coordinate system)
void removeCorrespondences (const std::string &id="correspondences", int viewport=0)
 Remove the specified correspondences from the display.
void removeOrientationMarkerWidgetAxes ()
 Disables the Orientatation Marker Widget so it is removed from the renderer.
bool removePointCloud (const std::string &id="cloud", int viewport=0)
 Removes a Point Cloud from screen, based on a given ID.
bool removePolygonMesh (const std::string &id="polygon", int viewport=0)
 Removes a PolygonMesh 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.
bool removeText3D (const std::string &id="cloud", int viewport=0)
 Removes an added 3D text from the scene, based on a given ID.
void renderView (int xres, int yres, pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
 Renders a virtual scene as seen from the camera viewpoint and returns the rendered point cloud. ATT: This method will only render the scene if only on viewport exists. Otherwise, returns an empty point cloud and exits immediately.
void renderViewTesselatedSphere (int xres, int yres, pcl::PointCloud< pcl::PointXYZ >::CloudVectorType &cloud, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &poses, std::vector< float > &enthropies, int tesselation_level, float view_angle=45, float radius_sphere=1, bool use_vertices=true)
 The purpose of this method is to render a CAD model added to the visualizer from different viewpoints in order to simulate partial views of model. The viewpoint locations are the vertices of a tesselated sphere build from an icosaheadron. The tesselation paremeter controls how many times the triangles of the original icosahedron are divided to approximate the sphere and thus the number of partial view generated for a model, with a tesselation_level of 0, 12 views are generated if use_vertices=true and 20 views if use_vertices=false.
void resetCamera ()
 Reset camera parameters and render.
void resetCameraViewpoint (const std::string &id="cloud")
 Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset.
void resetStoppedFlag ()
 Set the stopped flag back to false.
void saveScreenshot (const std::string &file)
 Save the current rendered image to disk, as a PNG screenshot.
void setBackgroundColor (const double &r, const double &g, const double &b, int viewport=0)
 Set the viewport's background color.
void setCameraClipDistances (double near, double far, int viewport=0)
 Set the camera clipping distances.
void setCameraFieldOfView (double fovy, int viewport=0)
 Set the camera vertical field of view.
void setCameraParameters (const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport=0)
 Set the camera parameters via an intrinsics and and extrinsics matrix.
void setCameraParameters (const Camera &camera, int viewport=0)
 Set the camera parameters by given a full camera data structure.
void setCameraPosition (double pos_x, double pos_y, double pos_z, double view_x, double view_y, double view_z, double up_x, double up_y, double up_z, int viewport=0)
 Set the camera pose given by position, viewpoint and up vector.
void setCameraPosition (double pos_x, double pos_y, double pos_z, double up_x, double up_y, double up_z, int viewport=0)
 Set the camera location and viewup according to the given arguments.
void setFullScreen (bool mode)
 Enables/Disabled the underlying window mode to full screen.
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 setPointCloudRenderingProperties (int property, double value, const std::string &id="cloud", int viewport=0)
 Set the rendering properties of a PointCloud.
bool setPointCloudSelected (const bool selected, const std::string &id="cloud")
 Set whether the point cloud is selected or not.
void setPosition (int x, int y)
 Set the position in screen coordinates.
void setRepresentationToPointsForAllActors ()
 Changes the visual representation for all actors to points representation.
void setRepresentationToSurfaceForAllActors ()
 Changes the visual representation for all actors to surface representation.
void setRepresentationToWireframeForAllActors ()
 Changes the visual representation for all actors to wireframe representation.
bool setShapeRenderingProperties (int property, double value, const std::string &id, int viewport=0)
 Set the rendering properties of a shape.
bool setShapeRenderingProperties (int property, double val1, double val2, double val3, const std::string &id, int viewport=0)
 Set the rendering properties of a shape (3x values - e.g., RGB)
void setShowFPS (bool show_fps)
 Sets whether the 2D overlay text showing the framerate of the window is displayed or not.
void setSize (int xw, int yw)
 Set the window size in screen coordinates.
void setupInteractor (vtkRenderWindowInteractor *iren, vtkRenderWindow *win)
 Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object attached to a given vtkRenderWindow.
void setupInteractor (vtkRenderWindowInteractor *iren, vtkRenderWindow *win, vtkInteractorStyle *style)
 Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object attached to a given vtkRenderWindow.
void setUseVbos (bool use_vbos)
 Use Vertex Buffer Objects renderers.
void setWindowBorders (bool mode)
 Enables or disable the underlying window borders.
void setWindowName (const std::string &name)
 Set the visualizer window name.
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.
template<typename PointT >
bool updateCorrespondences (const typename pcl::PointCloud< PointT >::ConstPtr &source_points, const typename pcl::PointCloud< PointT >::ConstPtr &target_points, const pcl::Correspondences &correspondences, int nth, const std::string &id="correspondences")
 Update the specified correspondences to the display.
template<typename PointT >
bool updatePointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &id="cloud")
 Updates the XYZ data for an existing cloud object id on screen.
template<typename PointT >
bool updatePointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const PointCloudGeometryHandler< PointT > &geometry_handler, const std::string &id="cloud")
 Updates the XYZ data for an existing cloud object id on screen.
template<typename PointT >
bool updatePointCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const PointCloudColorHandler< PointT > &color_handler, const std::string &id="cloud")
 Updates the XYZ data for an existing cloud object id on screen.
bool updatePointCloud (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud, const std::string &id="cloud")
 Updates the XYZ data for an existing cloud object id on screen.
bool updatePointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const std::string &id="cloud")
 Updates the XYZRGB data for an existing cloud object id on screen.
bool updatePointCloud (const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud")
 Updates the XYZRGBA data for an existing cloud object id on screen.
bool updatePointCloudPose (const std::string &id, const Eigen::Affine3f &pose)
 Set the pose of an existing point cloud.
template<typename PointT >
bool updatePolygonMesh (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::vector< pcl::Vertices > &vertices, const std::string &id="polygon")
 Update a PolygonMesh object on screen.
bool updatePolygonMesh (const pcl::PolygonMesh &polymesh, const std::string &id="polygon")
 Update a PolygonMesh object on screen.
bool updateShapePose (const std::string &id, const Eigen::Affine3f &pose)
 Set the pose of an existing shape.
template<typename PointT >
bool updateSphere (const PointT &center, double radius, double r, double g, double b, const std::string &id="sphere")
 Update an existing sphere shape from a point and a radius.
bool updateText (const std::string &text, int xpos, int ypos, const std::string &id="")
 Update a text to screen.
bool updateText (const std::string &text, int xpos, int ypos, double r, double g, double b, const std::string &id="")
 Update a text to screen.
bool updateText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b, const std::string &id="")
 Update a text to screen.
bool wasStopped () const
 Returns true when the user tried to close the window.
virtual ~PCLVisualizer ()
 PCL Visualizer destructor.

Static Public Member Functions

static void convertToEigenMatrix (const vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix, Eigen::Matrix4f &m)
 Convert vtkMatrix4x4 to an Eigen4f.
static void convertToVtkMatrix (const Eigen::Matrix4f &m, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
 Convert Eigen::Matrix4f to vtkMatrix4x4.
static void convertToVtkMatrix (const Eigen::Vector4f &origin, const Eigen::Quaternion< float > &orientation, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
 Convert origin and orientation to vtkMatrix4x4.

Protected Attributes

vtkSmartPointer
< vtkRenderWindowInteractor > 
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 allocVtkPolyData (vtkSmartPointer< vtkAppendPolyData > &polydata)
 Allocate a new polydata smartpointer. Internal.
void allocVtkPolyData (vtkSmartPointer< vtkPolyData > &polydata)
 Allocate a new polydata smartpointer. Internal.
void allocVtkUnstructuredGrid (vtkSmartPointer< vtkUnstructuredGrid > &polydata)
 Allocate a new unstructured grid smartpointer. Internal.
template<typename PointT >
void convertPointCloudToVTKPolyData (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, vtkSmartPointer< vtkPolyData > &polydata, vtkSmartPointer< vtkIdTypeArray > &initcells)
 Converts a PCL templated PointCloud object to a vtk polydata object.
template<typename PointT >
void convertPointCloudToVTKPolyData (const PointCloudGeometryHandler< PointT > &geometry_handler, vtkSmartPointer< vtkPolyData > &polydata, vtkSmartPointer< vtkIdTypeArray > &initcells)
 Converts a PCL templated PointCloud object to a vtk polydata object.
void convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler, vtkSmartPointer< vtkPolyData > &polydata, vtkSmartPointer< vtkIdTypeArray > &initcells)
 Converts a PCL templated PointCloud object to a vtk polydata object.
void createActorFromVTKDataSet (const vtkSmartPointer< vtkDataSet > &data, vtkSmartPointer< vtkActor > &actor, bool use_scalars=true)
 Internal method. Creates a vtk actor from a vtk polydata object.
void createActorFromVTKDataSet (const vtkSmartPointer< vtkDataSet > &data, vtkSmartPointer< vtkLODActor > &actor, bool use_scalars=true)
 Internal method. Creates a vtk actor from a vtk polydata object.
template<typename PointT >
bool fromHandlersToScreen (const PointCloudGeometryHandler< PointT > &geometry_handler, const PointCloudColorHandler< PointT > &color_handler, const std::string &id, int viewport, const Eigen::Vector4f &sensor_origin=Eigen::Vector4f(0, 0, 0, 0), const Eigen::Quaternion< float > &sensor_orientation=Eigen::Quaternion< float >(1, 0, 0, 0))
 Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.
template<typename PointT >
bool fromHandlersToScreen (const PointCloudGeometryHandler< PointT > &geometry_handler, const ColorHandlerConstPtr &color_handler, const std::string &id, int viewport, const Eigen::Vector4f &sensor_origin=Eigen::Vector4f(0, 0, 0, 0), const Eigen::Quaternion< float > &sensor_orientation=Eigen::Quaternion< float >(1, 0, 0, 0))
 Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.
bool fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, const ColorHandlerConstPtr &color_handler, const std::string &id, int viewport, const Eigen::Vector4f &sensor_origin=Eigen::Vector4f(0, 0, 0, 0), const Eigen::Quaternion< float > &sensor_orientation=Eigen::Quaternion< float >(1, 0, 0, 0))
 Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.
template<typename PointT >
bool fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler, const PointCloudColorHandler< PointT > &color_handler, const std::string &id, int viewport, const Eigen::Vector4f &sensor_origin=Eigen::Vector4f(0, 0, 0, 0), const Eigen::Quaternion< float > &sensor_orientation=Eigen::Quaternion< float >(1, 0, 0, 0))
 Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.
void getTransformationMatrix (const Eigen::Vector4f &origin, const Eigen::Quaternion< float > &orientation, Eigen::Matrix4f &transformation)
 Transform the point cloud viewpoint to a transformation matrix.
bool removeActorFromRenderer (const vtkSmartPointer< vtkLODActor > &actor, int viewport=0)
 Internal method. Removes a vtk actor from the screen.
bool removeActorFromRenderer (const vtkSmartPointer< vtkActor > &actor, int viewport=0)
 Internal method. Removes a vtk actor from the screen.
bool removeActorFromRenderer (const vtkSmartPointer< vtkProp > &actor, int viewport=0)
 Internal method. Adds a vtk actor to screen.
void updateCells (vtkSmartPointer< vtkIdTypeArray > &cells, vtkSmartPointer< vtkIdTypeArray > &initcells, vtkIdType nr_points)
 Updates a set of cells (vtkIdTypeArray) if the number of points in a cloud changes.

Private Attributes

vtkSmartPointer
< vtkOrientationMarkerWidget > 
axes_widget_
 Internal pointer to widget which contains a set of axes.
bool camera_set_
 Boolean that holds whether or not the camera parameters were manually initialized.
CloudActorMapPtr cloud_actor_map_
 Internal list with actor pointers and name IDs for point clouds.
CoordinateActorMap coordinate_actor_map_
 Internal list with actor pointers and viewpoint for coordinates.
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.
ShapeActorMapPtr shape_actor_map_
 Internal list with actor pointers and name IDs for shapes.
bool stopped_
 Set to false if the interaction loop is running.
vtkSmartPointer
< PCLVisualizerInteractorStyle
style_
 The render window interactor style.
int timer_id_
 Global timer ID. Used in destructor only.
vtkSmartPointer< FPSCallbackupdate_fps_
 The FPSCallback object for the current visualizer.
bool use_vbos_
 Boolean that holds whether or not to use the vtkVertexBufferObjectMapper.
vtkSmartPointer< vtkRenderWindow > win_
 The render window.

Detailed Description

PCL Visualizer main class.

Author:
Radu B. Rusu
Note:
This class can NOT be used across multiple threads. Only call functions of objects of this class from the same thread that they were created in! Some methods, e.g. addPointCloud, will crash if called from other threads.

Definition at line 85 of file pcl_visualizer.h.


Member Typedef Documentation

Definition at line 95 of file pcl_visualizer.h.

Definition at line 97 of file pcl_visualizer.h.

Definition at line 96 of file pcl_visualizer.h.

Definition at line 89 of file pcl_visualizer.h.

Definition at line 91 of file pcl_visualizer.h.

Definition at line 93 of file pcl_visualizer.h.

Definition at line 92 of file pcl_visualizer.h.

Definition at line 88 of file pcl_visualizer.h.


Constructor & Destructor Documentation

pcl::visualization::PCLVisualizer::PCLVisualizer ( const std::string name = "",
const bool  create_interactor = true 
)

PCL Visualizer constructor.

Parameters:
[in]namethe window name (empty by default)
[in]create_interactorif true (default), create an interactor, false otherwise

Definition at line 93 of file pcl_visualizer.cpp.

pcl::visualization::PCLVisualizer::PCLVisualizer ( int &  argc,
char **  argv,
const std::string name = "",
PCLVisualizerInteractorStyle style = PCLVisualizerInteractorStyle::New (),
const bool  create_interactor = true 
)

PCL Visualizer constructor.

Parameters:
[in]argc
[in]argv
[in]namethe window name (empty by default)
[in]styleinteractor style (defaults to PCLVisualizerInteractorStyle)
[in]create_interactorif true (default), create an interactor, false otherwise

Definition at line 155 of file pcl_visualizer.cpp.

PCL Visualizer destructor.

Definition at line 362 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:
[in]actora pointer to the vtk actor object
[in]viewportport where the actor should be added to (default: 0/all)
Note:
If viewport is set to 0, the actor will be added to all existing renders. To select a specific viewport use an integer between 1 and N.

Definition at line 974 of file pcl_visualizer.cpp.

template<typename P1 , typename P2 >
bool pcl::visualization::PCLVisualizer::addArrow ( const P1 &  pt1,
const P2 &  pt2,
double  r,
double  g,
double  b,
const std::string id = "arrow",
int  viewport = 0 
)

Add a line arrow segment between two points, and display the distance between them.

Parameters:
[in]pt1the first (start) point on the line
[in]pt2the second (end) point on the line
[in]rthe red channel of the color that the line should be rendered with
[in]gthe green channel of the color that the line should be rendered with
[in]bthe blue channel of the color that the line should be rendered with
[in]idthe arrow id/name (default: "arrow")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 455 of file pcl_visualizer.hpp.

template<typename P1 , typename P2 >
bool pcl::visualization::PCLVisualizer::addArrow ( const P1 &  pt1,
const P2 &  pt2,
double  r,
double  g,
double  b,
bool  display_length,
const std::string id = "arrow",
int  viewport = 0 
)

Add a line arrow segment between two points, and display the distance between them.

Parameters:
[in]pt1the first (start) point on the line
[in]pt2the second (end) point on the line
[in]rthe red channel of the color that the line should be rendered with
[in]gthe green channel of the color that the line should be rendered with
[in]bthe blue channel of the color that the line should be rendered with
[in]display_lengthtrue if the length should be displayed on the arrow as text
[in]idthe line id/name (default: "arrow")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 484 of file pcl_visualizer.hpp.

template<typename P1 , typename P2 >
bool pcl::visualization::PCLVisualizer::addArrow ( const P1 &  pt1,
const P2 &  pt2,
double  r_line,
double  g_line,
double  b_line,
double  r_text,
double  g_text,
double  b_text,
const std::string id = "arrow",
int  viewport = 0 
)

Add a line arrow segment between two points, and display the distance between them in a given color.

Parameters:
[in]pt1the first (start) point on the line
[in]pt2the second (end) point on the line
[in]r_linethe red channel of the color that the line should be rendered with
[in]g_linethe green channel of the color that the line should be rendered with
[in]b_linethe blue channel of the color that the line should be rendered with
[in]r_textthe red channel of the color that the text should be rendered with
[in]g_textthe green channel of the color that the text should be rendered with
[in]b_textthe blue channel of the color that the text should be rendered with
[in]idthe line id/name (default: "arrow")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 516 of file pcl_visualizer.hpp.

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:
[in]coefficientsthe model coefficients (x, y, radius)
[in]idthe circle id/name (default: "circle")
[in]viewport(optional) the id of the new viewport (default: 0)
 // The following are given (or computed using sample consensus techniques)
 // See SampleConsensusModelCircle2D for more information
 // float x, y, radius;

 pcl::ModelCoefficients circle_coeff;
 circle_coeff.values.resize (3);    // We need 3 values
 circle_coeff.values[0] = x;
 circle_coeff.values[1] = y;
 circle_coeff.values[2] = radius;

 vtkSmartPointer<vtkDataSet> data = pcl::visualization::create2DCircle (circle_coeff, z);

Definition at line 2442 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:
[in]coefficientsthe model coefficients (point_on_axis, axis_direction, radiu)
[in]idthe cone id/name (default: "cone")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2468 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:
[in]scalethe scale of the axes (default: 1)
[in]viewportthe view port where the 3D axes should be added (default: all)

Definition at line 495 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:
[in]scalethe scale of the axes (default: 1)
[in]xthe X position of the axes
[in]ythe Y position of the axes
[in]zthe Z position of the axes
[in]viewportthe view port where the 3D axes should be added (default: all)

Definition at line 534 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::addCoordinateSystem ( double  scale,
const Eigen::Affine3f &  t,
int  viewport = 0 
)

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

Parameters:
[in]scalethe scale of the axes (default: 1)
[in]ttransformation matrix
[in]viewportthe view port where the 3D axes should be added (default: all)

RPY Angles Rotate the reference frame by the angle roll about axis x Rotate the reference frame by the angle pitch about axis y Rotate the reference frame by the angle yaw about axis z

Description: Sets the orientation of the Prop3D. Orientation is specified as X,Y and Z rotations in that order, but they are performed as RotateZ, RotateX, and finally RotateY.

All axies use right hand rule. x=red axis, y=green axis, z=blue axis z direction is point into the screen. z \ \ \ -----------> x | | | | | | y

Definition at line 604 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addCorrespondences ( const typename pcl::PointCloud< PointT >::ConstPtr source_points,
const typename pcl::PointCloud< PointT >::ConstPtr target_points,
const std::vector< int > &  correspondences,
const std::string id = "correspondences",
int  viewport = 0 
)

Add the specified correspondences to the display.

Parameters:
[in]source_pointsThe source points
[in]target_pointsThe target points
[in]correspondencesThe mapping from source points to target points. Each element must be an index into target_points
[in]idthe polygon object id (default: "correspondences")
[in]viewportthe view port where the correspondences should be added (default: all)

Definition at line 892 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addCorrespondences ( const typename pcl::PointCloud< PointT >::ConstPtr source_points,
const typename pcl::PointCloud< PointT >::ConstPtr target_points,
const pcl::Correspondences correspondences,
int  nth,
const std::string id = "correspondences",
int  viewport = 0 
)

Add the specified correspondences to the display.

Parameters:
[in]source_pointsThe source points
[in]target_pointsThe target points
[in]correspondencesThe mapping from source points to target points. Each element must be an index into target_points
[in]nthdisplay only the Nth correspondence (e.g., skip the rest)
[in]idthe polygon object id (default: "correspondences")
[in]viewportthe view port where the correspondences should be added (default: all)

Definition at line 990 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addCorrespondences ( const typename pcl::PointCloud< PointT >::ConstPtr source_points,
const typename pcl::PointCloud< PointT >::ConstPtr target_points,
const pcl::Correspondences correspondences,
const std::string id = "correspondences",
int  viewport = 0 
) [inline]

Add the specified correspondences to the display.

Parameters:
[in]source_pointsThe source points
[in]target_pointsThe target points
[in]correspondencesThe mapping from source points to target points. Each element must be an index into target_points
[in]idthe polygon object id (default: "correspondences")
[in]viewportthe view port where the correspondences should be added (default: all)

Definition at line 929 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::addCube ( const pcl::ModelCoefficients coefficients,
const std::string id = "cube",
int  viewport = 0 
)

Add a cube from a set of given model coefficients.

Parameters:
[in]coefficientsthe model coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth)
[in]idthe cube id/name (default: "cube")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2128 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addCube ( const Eigen::Vector3f &  translation,
const Eigen::Quaternionf &  rotation,
double  width,
double  height,
double  depth,
const std::string id = "cube",
int  viewport = 0 
)

Add a cube from a set of given model coefficients.

Parameters:
[in]translationa translation to apply to the cube from 0,0,0
[in]rotationa quaternion-based rotation to apply to the cube
[in]widththe cube's width
[in]heightthe cube's height
[in]depththe cube's depth
[in]idthe cube id/name (default: "cube")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2155 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addCube ( float  x_min,
float  x_max,
float  y_min,
float  y_max,
float  z_min,
float  z_max,
double  r = 1.0,
double  g = 1.0,
double  b = 1.0,
const std::string id = "cube",
int  viewport = 0 
)

Add a cube.

Parameters:
[in]x_minthe min X coordinate
[in]x_maxthe max X coordinate
[in]y_minthe min Y coordinate
[in]y_maxthe max Y coordinate
[in]z_minthe min Z coordinate
[in]z_maxthe max Z coordinate
[in]rhow much red (0.0 -> 1.0)
[in]ghow much green (0.0 -> 1.0)
[in]bhow much blue (0.0 -> 1.0)
[in]idthe cube id/name (default: "cube")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2184 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:
[in]coefficientsthe model coefficients (point_on_axis, axis_direction, radius)
[in]idthe cylinder id/name (default: "cylinder")
[in]viewport(optional) the id of the new viewport (default: 0)
 // The following are given (or computed using sample consensus techniques)
 // See SampleConsensusModelCylinder for more information.
 // Eigen::Vector3f pt_on_axis, axis_direction;
 // float radius;

 pcl::ModelCoefficients cylinder_coeff;
 cylinder_coeff.values.resize (7);    // We need 7 values
 cylinder_coeff.values[0] = pt_on_axis.x ();
 cylinder_coeff.values[1] = pt_on_axis.y ();
 cylinder_coeff.values[2] = pt_on_axis.z ();

 cylinder_coeff.values[3] = axis_direction.x ();
 cylinder_coeff.values[4] = axis_direction.y ();
 cylinder_coeff.values[5] = axis_direction.z ();

 cylinder_coeff.values[6] = radius;

 addCylinder (cylinder_coeff);

Definition at line 2101 of file pcl_visualizer.cpp.

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

Add a line segment from two points.

Parameters:
[in]pt1the first (start) point on the line
[in]pt2the second (end) point on the line
[in]idthe line id/name (default: "line")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 550 of file pcl_visualizer.hpp.

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 
)

Add a line segment from two points.

Parameters:
[in]pt1the first (start) point on the line
[in]pt2the second (end) point on the line
[in]rthe red channel of the color that the line should be rendered with
[in]gthe green channel of the color that the line should be rendered with
[in]bthe blue channel of the color that the line should be rendered with
[in]idthe line id/name (default: "line")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 428 of file pcl_visualizer.hpp.

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:
[in]coefficientsthe model coefficients (point_on_line, direction)
[in]idthe line id/name (default: "line")
[in]viewport(optional) the id of the new viewport (default: 0)
 // The following are given (or computed using sample consensus techniques)
 // See SampleConsensusModelLine for more information
 // Eigen::Vector3f point_on_line, line_direction;

 pcl::ModelCoefficients line_coeff;
 line_coeff.values.resize (6);    // We need 6 values
 line_coeff.values[0] = point_on_line.x ();
 line_coeff.values[1] = point_on_line.y ();
 line_coeff.values[2] = point_on_line.z ();

 line_coeff.values[3] = line_direction.x ();
 line_coeff.values[4] = line_direction.y ();
 line_coeff.values[5] = line_direction.z ();

 addLine (line_coeff);

Definition at line 2359 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:
[in]filenameof the ply file
[in]idthe model id/name (default: "PLYModel")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2297 of file pcl_visualizer.cpp.

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:
[in]filenameof the ply file
[in]transformtransformation to apply
[in]idthe model id/name (default: "PLYModel")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2325 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addModelFromPolyData ( vtkSmartPointer< vtkPolyData >  polydata,
const std::string id = "PolyData",
int  viewport = 0 
)

Add a vtkPolydata as a mesh.

Parameters:
[in]polydatavtkPolyData
[in]idthe model id/name (default: "PolyData")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2242 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addModelFromPolyData ( vtkSmartPointer< vtkPolyData >  polydata,
vtkSmartPointer< vtkTransform >  transform,
const std::string id = "PolyData",
int  viewport = 0 
)

Add a vtkPolydata as a mesh.

Parameters:
[in]polydatavtkPolyData
[in]transformtransformation to apply
[in]idthe model id/name (default: "PolyData")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 2266 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::addOrientationMarkerWidgetAxes ( vtkRenderWindowInteractor *  interactor)

Adds a widget which shows an interactive axes display for orientation.

Parameters:
[in]interactor- Pointer to the vtk interactor object used by the PCLVisualizer window

Definition at line 454 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:
[in]coefficientsthe model coefficients (a, b, c, d with ax+by+cz+d=0)
[in]idthe plane id/name (default: "plane")
[in]viewport(optional) the id of the new viewport (default: 0)
 // The following are given (or computed using sample consensus techniques)
 // See SampleConsensusModelPlane for more information
 // Eigen::Vector4f plane_parameters;

 pcl::ModelCoefficients plane_coeff;
 plane_coeff.values.resize (4);    // We need 4 values
 plane_coeff.values[0] = plane_parameters.x ();
 plane_coeff.values[1] = plane_parameters.y ();
 plane_coeff.values[2] = plane_parameters.z ();
 plane_coeff.values[3] = plane_parameters.w ();

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

Definition at line 2390 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addPlane ( const pcl::ModelCoefficients coefficients,
double  x,
double  y,
double  z,
const std::string id = "plane",
int  viewport = 0 
)

Definition at line 2416 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const std::string id = "cloud",
int  viewport = 0 
)

Add a Point Cloud (templated) to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id (default: cloud)
viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 66 of file pcl_visualizer.hpp.

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

Add a Point Cloud (templated) to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handleruse a geometry handler object to extract the XYZ data
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 77 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const GeometryHandlerConstPtr geometry_handler,
const std::string id = "cloud",
int  viewport = 0 
)

Add a Point Cloud (templated) to screen.

Because the geometry handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active geometric handler. This makes it possible to switch between different geometric handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using Alt+0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handleruse a geometry handler object to extract the XYZ data
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 98 of file pcl_visualizer.hpp.

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

Add a Point Cloud (templated) to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]color_handlera specific PointCloud visualizer handler for colors
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 121 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const ColorHandlerConstPtr color_handler,
const std::string id = "cloud",
int  viewport = 0 
)

Add a Point Cloud (templated) to screen.

Because the color handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active color handler. This makes it possible to switch between different color handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using 0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]color_handlera specific PointCloud visualizer handler for colors
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 146 of file pcl_visualizer.hpp.

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

Add a Point Cloud (templated) to screen.

Because the geometry/color handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active handler. This makes it possible to switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using [Alt+]0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handlera specific PointCloud visualizer handler for geometry
[in]color_handlera specific PointCloud visualizer handler for colors
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 167 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PCLPointCloud2::ConstPtr cloud,
const GeometryHandlerConstPtr geometry_handler,
const ColorHandlerConstPtr color_handler,
const Eigen::Vector4f &  sensor_origin,
const Eigen::Quaternion< float > &  sensor_orientation,
const std::string id = "cloud",
int  viewport = 0 
)

Add a binary blob Point Cloud to screen.

Because the geometry/color handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active handler. This makes it possible to switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using [Alt+]0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handlera specific PointCloud visualizer handler for geometry
[in]color_handlera specific PointCloud visualizer handler for colors
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 3842 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PCLPointCloud2::ConstPtr cloud,
const GeometryHandlerConstPtr geometry_handler,
const Eigen::Vector4f &  sensor_origin,
const Eigen::Quaternion< float > &  sensor_orientation,
const std::string id = "cloud",
int  viewport = 0 
)

Add a binary blob Point Cloud to screen.

Because the geometry/color handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active handler. This makes it possible to switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using [Alt+]0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handlera specific PointCloud visualizer handler for geometry
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 3865 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PCLPointCloud2::ConstPtr cloud,
const ColorHandlerConstPtr color_handler,
const Eigen::Vector4f &  sensor_origin,
const Eigen::Quaternion< float > &  sensor_orientation,
const std::string id = "cloud",
int  viewport = 0 
)

Add a binary blob Point Cloud to screen.

Because the geometry/color handler is given as a pointer, it will be pushed back to the list of available handlers, rather than replacing the current active handler. This makes it possible to switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor interface (using [Alt+]0..9).

Parameters:
[in]cloudthe input point cloud dataset
[in]color_handlera specific PointCloud visualizer handler for colors
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 3889 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr 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.

Parameters:
[in]cloudthe input point cloud dataset
[in]color_handlera specific PointCloud visualizer handler for colors
[in]geometry_handleruse a geometry handler object to extract the XYZ data
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 188 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud,
const std::string id = "cloud",
int  viewport = 0 
) [inline]

Add a PointXYZ Point Cloud to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 768 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr cloud,
const std::string id = "cloud",
int  viewport = 0 
) [inline]

Add a PointXYZRGB Point Cloud to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 781 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::addPointCloud ( const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr cloud,
const std::string id = "cloud",
int  viewport = 0 
) [inline]

Add a PointXYZRGBA Point Cloud to screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 794 of file pcl_visualizer.h.

template<typename PointT , typename GradientT >
bool pcl::visualization::PCLVisualizer::addPointCloudIntensityGradients ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const typename pcl::PointCloud< GradientT >::ConstPtr gradients,
int  level = 100,
double  scale = 1e-6,
const std::string id = "cloud",
int  viewport = 0 
)

Add the estimated surface intensity gradients of a Point Cloud to screen.

Parameters:
[in]cloudthe input point cloud dataset containing the XYZ data
[in]gradientsthe input point cloud dataset containing the intensity gradient data
[in]leveldisplay only every level'th point (default: 100)
[in]scalethe intensity gradient arrow scale (default: 1e-6m)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 817 of file pcl_visualizer.hpp.

template<typename PointNT >
bool pcl::visualization::PCLVisualizer::addPointCloudNormals ( const typename pcl::PointCloud< PointNT >::ConstPtr cloud,
int  level = 100,
float  scale = 0.02f,
const std::string id = "cloud",
int  viewport = 0 
)

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

Parameters:
[in]cloudthe input point cloud dataset containing XYZ data and normals
[in]leveldisplay only every level'th point (default: 100)
[in]scalethe normal arrow scale (default: 0.02m)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 696 of file pcl_visualizer.hpp.

template<typename PointT , typename PointNT >
bool pcl::visualization::PCLVisualizer::addPointCloudNormals ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const typename pcl::PointCloud< PointNT >::ConstPtr normals,
int  level = 100,
float  scale = 0.02f,
const std::string id = "cloud",
int  viewport = 0 
)

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

Parameters:
[in]cloudthe input point cloud dataset containing the XYZ data
[in]normalsthe input point cloud dataset containing the normal data
[in]leveldisplay only every level'th point (default: 100)
[in]scalethe normal arrow scale (default: 0.02m)
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 705 of file pcl_visualizer.hpp.

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

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

Parameters:
[in]cloudthe input point cloud dataset containing the XYZ data
[in]normalsthe input point cloud dataset containing the normal data
[in]pcsthe input point cloud dataset containing the principal curvatures data
[in]leveldisplay only every level'th point. Default: 100
[in]scalethe normal arrow scale. Default: 1.0
[in]idthe point cloud object id. Default: "cloud"
[in]viewportthe view port where the Point Cloud should be added (default: all)

Definition at line 791 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPolygon ( const typename pcl::PointCloud< PointT >::ConstPtr 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)

Parameters:
[in]cloudthe point cloud dataset representing the polygon
[in]rthe red channel of the color that the polygon should be rendered with
[in]gthe green channel of the color that the polygon should be rendered with
[in]bthe blue channel of the color that the polygon should be rendered with
[in]id(optional) the polygon id/name (default: "polygon")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 310 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPolygon ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const std::string id = "polygon",
int  viewport = 0 
)

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

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

Definition at line 419 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPolygon ( const pcl::PlanarPolygon< PointT > &  polygon,
double  r,
double  g,
double  b,
const std::string id = "polygon",
int  viewport = 0 
)

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

Parameters:
[in]polygonthe polygon to draw
[in]rthe red channel of the color that the polygon should be rendered with
[in]gthe green channel of the color that the polygon should be rendered with
[in]bthe blue channel of the color that the polygon should be rendered with
[in]idthe polygon id/name (default: "polygon")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 364 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::addPolygonMesh ( const pcl::PolygonMesh polymesh,
const std::string id = "polygon",
int  viewport = 0 
)

Add a PolygonMesh object to screen.

Parameters:
[in]polymeshthe polygonal mesh
[in]idthe polygon object id (default: "polygon")
[in]viewportthe view port where the PolygonMesh should be added (default: all)

Definition at line 2790 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addPolygonMesh ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const std::vector< pcl::Vertices > &  vertices,
const std::string id = "polygon",
int  viewport = 0 
)

Add a PolygonMesh object to screen.

Parameters:
[in]cloudthe polygonal mesh point cloud
[in]verticesthe polygonal mesh vertices
[in]idthe polygon object id (default: "polygon")
[in]viewportthe view port where the PolygonMesh should be added (default: all)

Definition at line 1522 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::addPolylineFromPolygonMesh ( const pcl::PolygonMesh polymesh,
const std::string id = "polyline",
int  viewport = 0 
)

Add a Polygonline from a polygonMesh object to screen.

Parameters:
[in]polymeshthe polygonal mesh from where the polylines will be extracted
[in]idthe polygon object id (default: "polygon")
[in]viewportthe view port where the PolygonMesh should be added (default: all)

Definition at line 3012 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addSphere ( const PointT center,
double  radius,
const std::string id = "sphere",
int  viewport = 0 
)

Add a sphere shape from a point and a radius.

Parameters:
[in]centerthe center of the sphere
[in]radiusthe radius of the sphere
[in]idthe sphere id/name (default: "sphere")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 599 of file pcl_visualizer.hpp.

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 
)

Add a sphere shape from a point and a radius.

Parameters:
[in]centerthe center of the sphere
[in]radiusthe radius of the sphere
[in]rthe red channel of the color that the sphere should be rendered with
[in]gthe green channel of the color that the sphere should be rendered with
[in]bthe blue channel of the color that the sphere should be rendered with
[in]idthe sphere id/name (default: "sphere")
[in]viewport(optional) the id of the new viewport (default: 0)

Definition at line 557 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:
[in]coefficientsthe model coefficients (sphere center, radius)
[in]idthe sphere id/name (default: "sphere")
[in]viewport(optional) the id of the new viewport (default: 0)
 // The following are given (or computed using sample consensus techniques)
 // See SampleConsensusModelSphere for more information
 // Eigen::Vector3f sphere_center;
 // float radius;

 pcl::ModelCoefficients sphere_coeff;
 sphere_coeff.values.resize (4);    // We need 4 values
 sphere_coeff.values[0] = sphere_center.x ();
 sphere_coeff.values[1] = sphere_center.y ();
 sphere_coeff.values[2] = sphere_center.z ();

 sphere_coeff.values[3] = radius;

 addSphere (sphere_coeff);

Definition at line 2215 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:
[in]textthe text to add
[in]xposthe X position on screen where the text should be added
[in]yposthe Y position on screen where the text should be added
[in]idthe text object id (default: equal to the "text" parameter)
[in]viewportthe view port (default: all)

Definition at line 2539 of file pcl_visualizer.cpp.

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

Add a text to screen.

Parameters:
[in]textthe text to add
[in]xposthe X position on screen where the text should be added
[in]yposthe Y position on screen where the text should be added
[in]rthe red color value
[in]gthe green color value
[in]bthe blue color vlaue
[in]idthe text object id (default: equal to the "text" parameter)
[in]viewportthe view port (default: all)

Definition at line 2575 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::addText ( const std::string text,
int  xpos,
int  ypos,
int  fontsize,
double  r,
double  g,
double  b,
const std::string id = "",
int  viewport = 0 
)

Add a text to screen.

Parameters:
[in]textthe text to add
[in]xposthe X position on screen where the text should be added
[in]yposthe Y position on screen where the text should be added
[in]fontsizethe fontsize of the text
[in]rthe red color value
[in]gthe green color value
[in]bthe blue color vlaue
[in]idthe text object id (default: equal to the "text" parameter)
[in]viewportthe view port (default: all)

Definition at line 2611 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::addText3D ( const std::string text,
const PointT position,
double  textScale = 1.0,
double  r = 1.0,
double  g = 1.0,
double  b = 1.0,
const std::string id = "",
int  viewport = 0 
)

Add a 3d text to the scene.

Parameters:
[in]textthe text to add
[in]positionthe world position where the text should be added
[in]textScalethe scale of the text to render
[in]rthe red color value
[in]gthe green color value
[in]bthe blue color value
[in]idthe text object id (default: equal to the "text" parameter)
[in]viewportthe view port (default: all)

Definition at line 630 of file pcl_visualizer.hpp.

void pcl::visualization::PCLVisualizer::allocVtkPolyData ( vtkSmartPointer< vtkAppendPolyData > &  polydata) [private]

Allocate a new polydata smartpointer. Internal.

Parameters:
[out]polydatathe resultant poly data

Definition at line 3769 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::allocVtkPolyData ( vtkSmartPointer< vtkPolyData > &  polydata) [private]

Allocate a new polydata smartpointer. Internal.

Parameters:
[out]polydatathe resultant poly data

Definition at line 3775 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::allocVtkUnstructuredGrid ( vtkSmartPointer< vtkUnstructuredGrid > &  polydata) [private]

Allocate a new unstructured grid smartpointer. Internal.

Parameters:
[out]polydatathe resultant poly data

Definition at line 3781 of file pcl_visualizer.cpp.

Checks whether the camera parameters were manually loaded from file.

Definition at line 1620 of file pcl_visualizer.cpp.

Stop the interaction and close the visualizaton window.

Definition at line 3952 of file pcl_visualizer.cpp.

template<typename PointT >
void pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
vtkSmartPointer< vtkPolyData > &  polydata,
vtkSmartPointer< vtkIdTypeArray > &  initcells 
) [private]

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

Parameters:
[in]cloudthe input PCL PointCloud dataset
[out]polydatathe resultant polydata containing the cloud
[out]initcellsa list of cell indices used for the conversion. This can be set once and then passed around to speed up the conversion.

Definition at line 212 of file pcl_visualizer.hpp.

template<typename PointT >
void pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const PointCloudGeometryHandler< PointT > &  geometry_handler,
vtkSmartPointer< vtkPolyData > &  polydata,
vtkSmartPointer< vtkIdTypeArray > &  initcells 
) [private]

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

Parameters:
[in]geometry_handlerthe geometry handler object used to extract the XYZ data
[out]polydatathe resultant polydata containing the cloud
[out]initcellsa list of cell indices used for the conversion. This can be set once and then passed around to speed up the conversion.

Definition at line 277 of file pcl_visualizer.hpp.

void pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData ( const GeometryHandlerConstPtr geometry_handler,
vtkSmartPointer< vtkPolyData > &  polydata,
vtkSmartPointer< vtkIdTypeArray > &  initcells 
) [private]

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

Parameters:
[in]geometry_handlerthe geometry handler object used to extract the XYZ data
[out]polydatathe resultant polydata containing the cloud
[out]initcellsa list of cell indices used for the conversion. This can be set once and then passed around to speed up the conversion.

Definition at line 1206 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::convertToEigenMatrix ( const vtkSmartPointer< vtkMatrix4x4 > &  vtk_matrix,
Eigen::Matrix4f &  m 
) [static]

Convert vtkMatrix4x4 to an Eigen4f.

Parameters:
[in]vtk_matrixthe original VTK 4x4 matrix
[out]mthe resultant Eigen 4x4 matrix

Definition at line 3831 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::convertToVtkMatrix ( const Eigen::Matrix4f &  m,
vtkSmartPointer< vtkMatrix4x4 > &  vtk_matrix 
) [static]

Convert Eigen::Matrix4f to vtkMatrix4x4.

Parameters:
[in]mthe input Eigen matrix
[out]vtk_matrixthe resultant VTK matrix

Definition at line 3820 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::convertToVtkMatrix ( const Eigen::Vector4f &  origin,
const Eigen::Quaternion< float > &  orientation,
vtkSmartPointer< vtkMatrix4x4 > &  vtk_matrix 
) [static]

Convert origin and orientation to vtkMatrix4x4.

Parameters:
[in]originthe point cloud origin
[in]orientationthe point cloud orientation
[out]vtk_matrixthe resultant VTK 4x4 matrix

Definition at line 3800 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::createActorFromVTKDataSet ( const vtkSmartPointer< vtkDataSet > &  data,
vtkSmartPointer< vtkActor > &  actor,
bool  use_scalars = true 
) [private]

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

Parameters:
[in]datathe vtk polydata object to create an actor for
[out]actorthe resultant vtk actor object
[in]use_scalarsset scalar properties to the mapper if it exists in the data. Default: true.

FIXME disabling backface culling due to known VTK bug: vtkTextActors are not shown when there is a vtkActor with backface culling on present in the scene Please see VTK bug tracker for more details: http://www.vtk.org/Bug/view.php?id=12588

FIXME disabling backface culling due to known VTK bug: vtkTextActors are not shown when there is a vtkActor with backface culling on present in the scene Please see VTK bug tracker for more details: http://www.vtk.org/Bug/view.php?id=12588

Definition at line 1129 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::createActorFromVTKDataSet ( const vtkSmartPointer< vtkDataSet > &  data,
vtkSmartPointer< vtkLODActor > &  actor,
bool  use_scalars = true 
) [private]

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

Parameters:
[in]datathe vtk polydata object to create an actor for
[out]actorthe resultant vtk actor object
[in]use_scalarsset scalar properties to the mapper if it exists in the data. Default: true.

FIXME disabling backface culling due to known VTK bug: vtkTextActors are not shown when there is a vtkActor with backface culling on present in the scene Please see VTK bug tracker for more details: http://www.vtk.org/Bug/view.php?id=12588

FIXME disabling backface culling due to known VTK bug: vtkTextActors are not shown when there is a vtkActor with backface culling on present in the scene Please see VTK bug tracker for more details: http://www.vtk.org/Bug/view.php?id=12588

Definition at line 1055 of file pcl_visualizer.cpp.

Create the internal Interactor object.

Definition at line 226 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:
[in]xminthe minimum X coordinate for the viewport (0.0 <= 1.0)
[in]yminthe minimum Y coordinate for the viewport (0.0 <= 1.0)
[in]xmaxthe maximum X coordinate for the viewport (0.0 <= 1.0)
[in]ymaxthe maximum Y coordinate for the viewport (0.0 <= 1.0)
[in]viewportthe id of the new viewport
Note:
If no renderer for the current window exists, one will be created, and the viewport will be set to 0 ('all'). In case one or multiple renderers do exist, the viewport ID will be set to the total number of renderers - 1.

Definition at line 2494 of file pcl_visualizer.cpp.

Create a new separate camera for the given viewport.

Parameters:
[in]viewportthe viewport to create a new camera for.

Definition at line 2518 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::fromHandlersToScreen ( const PointCloudGeometryHandler< PointT > &  geometry_handler,
const PointCloudColorHandler< PointT > &  color_handler,
const std::string id,
int  viewport,
const Eigen::Vector4f &  sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
const Eigen::Quaternion< float > &  sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0) 
) [private]

Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.

Parameters:
[in]geometry_handlerthe geometric handler that contains the XYZ data
[in]color_handlerthe color handler that contains the "RGB" (scalar) data
[in]idthe point cloud object id
[in]viewportthe view port where the Point Cloud should be added
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)

Definition at line 1191 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::fromHandlersToScreen ( const PointCloudGeometryHandler< PointT > &  geometry_handler,
const ColorHandlerConstPtr color_handler,
const std::string id,
int  viewport,
const Eigen::Vector4f &  sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
const Eigen::Quaternion< float > &  sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0) 
) [private]

Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.

Parameters:
[in]geometry_handlerthe geometric handler that contains the XYZ data
[in]color_handlerthe color handler that contains the "RGB" (scalar) data
[in]idthe point cloud object id
[in]viewportthe view port where the Point Cloud should be added
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)

Definition at line 1255 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::fromHandlersToScreen ( const GeometryHandlerConstPtr geometry_handler,
const ColorHandlerConstPtr color_handler,
const std::string id,
int  viewport,
const Eigen::Vector4f &  sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
const Eigen::Quaternion< float > &  sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0) 
) [private]

Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.

Parameters:
[in]geometry_handlerthe geometric handler that contains the XYZ data
[in]color_handlerthe color handler that contains the "RGB" (scalar) data
[in]idthe point cloud object id
[in]viewportthe view port where the Point Cloud should be added
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)

Definition at line 3657 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::fromHandlersToScreen ( const GeometryHandlerConstPtr geometry_handler,
const PointCloudColorHandler< PointT > &  color_handler,
const std::string id,
int  viewport,
const Eigen::Vector4f &  sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
const Eigen::Quaternion< float > &  sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0) 
) [private]

Internal function which converts the information present in the geometric and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds all the required information to the internal cloud_actor_map_ object.

Parameters:
[in]geometry_handlerthe geometric handler that contains the XYZ data
[in]color_handlerthe color handler that contains the "RGB" (scalar) data
[in]idthe point cloud object id
[in]viewportthe view port where the Point Cloud should be added
[in]sensor_originthe origin of the cloud data in global coordinates (defaults to 0,0,0)
[in]sensor_orientationthe orientation of the cloud data in global coordinates (defaults to 1,0,0,0)

Definition at line 1320 of file pcl_visualizer.hpp.

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

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

Parameters:
[in]argc
[in]argv

Definition at line 1970 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::getCameras ( std::vector< Camera > &  cameras)

Get the current camera parameters.

Definition at line 1681 of file pcl_visualizer.cpp.

Return a pointer to the CloudActorMap this visualizer uses.

Definition at line 1624 of file pcl_visualizer.h.

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

Parameters:
[in]idthe point cloud object id

Definition at line 3976 of file pcl_visualizer.cpp.

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

Parameters:
[in]idthe point cloud object id

Definition at line 3987 of file pcl_visualizer.cpp.

Get a pointer to the current interactor style used.

Definition at line 1676 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:
[in]propertythe property type
[in]valuethe resultant property value
[in]idthe point cloud object id (default: cloud)

Definition at line 1299 of file pcl_visualizer.cpp.

vtkSmartPointer<vtkRendererCollection> pcl::visualization::PCLVisualizer::getRendererCollection ( ) [inline]

Return a pointer to the underlying VTK Renderer Collection.

Definition at line 1617 of file pcl_visualizer.h.

vtkSmartPointer<vtkRenderWindow> pcl::visualization::PCLVisualizer::getRenderWindow ( ) [inline]

Return a pointer to the underlying VTK Render Window used.

Definition at line 1610 of file pcl_visualizer.h.

void pcl::visualization::PCLVisualizer::getTransformationMatrix ( const Eigen::Vector4f &  origin,
const Eigen::Quaternion< float > &  orientation,
Eigen::Matrix4f &  transformation 
) [private]

Transform the point cloud viewpoint to a transformation matrix.

Parameters:
[in]originthe camera origin
[in]orientationthe camera orientation
[out]transformationthe camera transformation matrix

Definition at line 3788 of file pcl_visualizer.cpp.

Eigen::Affine3f pcl::visualization::PCLVisualizer::getViewerPose ( int  viewport = 0)

Get the current viewing pose.

TODO replace this ugly thing with matrix.block () = vector3f

Definition at line 1710 of file pcl_visualizer.cpp.

Initialize camera parameters with some default values.

Definition at line 1586 of file pcl_visualizer.cpp.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerAreaPickingCallback ( boost::function< void(const pcl::visualization::AreaPickingEvent &)>  cb)

Register a callback function for area picking events.

Parameters:
[in]cba boost function that will be registered as a callback for an area picking event
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 411 of file pcl_visualizer.cpp.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerAreaPickingCallback ( void(*)(const pcl::visualization::AreaPickingEvent &, void *)  callback,
void *  cookie = NULL 
)

Register a callback function for area picking events.

Parameters:
[in]callbackthe function that will be registered as a callback for an area picking event
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 418 of file pcl_visualizer.cpp.

template<typename T >
boost::signals2::connection pcl::visualization::PCLVisualizer::registerAreaPickingCallback ( void(T::*)(const pcl::visualization::AreaPickingEvent &, void *)  callback,
T &  instance,
void *  cookie = NULL 
) [inline]

Register a callback function for area picking events.

Parameters:
[in]callbackthe member function that will be registered as a callback for an area picking event
[in]instanceinstance to the class that implements the callback function
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 249 of file pcl_visualizer.h.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerKeyboardCallback ( boost::function< void(const pcl::visualization::KeyboardEvent &)>  cb)

Register a callback boost::function for keyboard events.

Parameters:
[in]cba boost function that will be registered as a callback for a keyboard event
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 383 of file pcl_visualizer.cpp.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerKeyboardCallback ( void(*)(const pcl::visualization::KeyboardEvent &, void *)  callback,
void *  cookie = NULL 
) [inline]

Register a callback function for keyboard events.

Parameters:
[in]callbackthe function that will be registered as a callback for a keyboard event
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 153 of file pcl_visualizer.h.

template<typename T >
boost::signals2::connection pcl::visualization::PCLVisualizer::registerKeyboardCallback ( void(T::*)(const pcl::visualization::KeyboardEvent &, void *)  callback,
T &  instance,
void *  cookie = NULL 
) [inline]

Register a callback function for keyboard events.

Parameters:
[in]callbackthe member function that will be registered as a callback for a keyboard event
[in]instanceinstance to the class that implements the callback function
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 165 of file pcl_visualizer.h.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerMouseCallback ( boost::function< void(const pcl::visualization::MouseEvent &)>  cb)

Register a callback function for mouse events.

Parameters:
[in]cba boost function that will be registered as a callback for a mouse event
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 390 of file pcl_visualizer.cpp.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerMouseCallback ( void(*)(const pcl::visualization::MouseEvent &, void *)  callback,
void *  cookie = NULL 
) [inline]

Register a callback function for mouse events.

Parameters:
[in]callbackthe function that will be registered as a callback for a mouse event
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 183 of file pcl_visualizer.h.

template<typename T >
boost::signals2::connection pcl::visualization::PCLVisualizer::registerMouseCallback ( void(T::*)(const pcl::visualization::MouseEvent &, void *)  callback,
T &  instance,
void *  cookie = NULL 
) [inline]

Register a callback function for mouse events.

Parameters:
[in]callbackthe member function that will be registered as a callback for a mouse event
[in]instanceinstance to the class that implements the callback function
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 195 of file pcl_visualizer.h.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerPointPickingCallback ( boost::function< void(const pcl::visualization::PointPickingEvent &)>  cb)

Register a callback function for point picking events.

Parameters:
[in]cba boost function that will be registered as a callback for a point picking event
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 397 of file pcl_visualizer.cpp.

boost::signals2::connection pcl::visualization::PCLVisualizer::registerPointPickingCallback ( void(*)(const pcl::visualization::PointPickingEvent &, void *)  callback,
void *  cookie = NULL 
)

Register a callback function for point picking events.

Parameters:
[in]callbackthe function that will be registered as a callback for a point picking event
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 404 of file pcl_visualizer.cpp.

template<typename T >
boost::signals2::connection pcl::visualization::PCLVisualizer::registerPointPickingCallback ( void(T::*)(const pcl::visualization::PointPickingEvent &, void *)  callback,
T &  instance,
void *  cookie = NULL 
) [inline]

Register a callback function for point picking events.

Parameters:
[in]callbackthe member function that will be registered as a callback for a point picking event
[in]instanceinstance to the class that implements the callback function
[in]cookieuser data that is passed to the callback
Returns:
a connection object that allows to disconnect the callback function.

Definition at line 222 of file pcl_visualizer.h.

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

Internal method. Removes a vtk actor from the screen.

Parameters:
[in]actora pointer to the vtk actor object
[in]viewportthe view port where the actor should be removed from (default: all)

Definition at line 894 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::removeActorFromRenderer ( const vtkSmartPointer< vtkActor > &  actor,
int  viewport = 0 
) [private]

Internal method. Removes a vtk actor from the screen.

Parameters:
[in]actora pointer to the vtk actor object
[in]viewportthe view port where the actor should be removed from (default: all)

Definition at line 934 of file pcl_visualizer.cpp.

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

Internal method. Adds a vtk actor to screen.

Parameters:
[in]actora pointer to the vtk actor object
[in]viewportthe view port where the actor should be added to (default: all)

Definition at line 999 of file pcl_visualizer.cpp.

Remove all point cloud data on screen from the given viewport.

Parameters:
[in]viewportview port from where the clouds should be removed (default: all)

Definition at line 759 of file pcl_visualizer.cpp.

Remove all 3D shape data on screen from the given viewport.

Parameters:
[in]viewportview port from where the shapes should be removed (default: all)

Definition at line 775 of file pcl_visualizer.cpp.

Removes a previously added 3D axes (coordinate system)

Parameters:
[in]viewportview port where the 3D axes should be removed from (default: all)

Definition at line 656 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::removeCorrespondences ( const std::string id = "correspondences",
int  viewport = 0 
)

Remove the specified correspondences from the display.

Parameters:
[in]idthe polygon correspondences object id (i.e., given on addCorrespondences)
[in]viewportview port from where the correspondences should be removed (default: all)

Definition at line 3968 of file pcl_visualizer.cpp.

Disables the Orientatation Marker Widget so it is removed from the renderer.

Definition at line 478 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:
[in]idthe point cloud object id (i.e., given on addPointCloud)
[in]viewportview port from where the Point Cloud should be removed (default: all)
Returns:
true if the point cloud is successfully removed and false if the point cloud is not actually displayed

Definition at line 676 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::removePolygonMesh ( const std::string id = "polygon",
int  viewport = 0 
) [inline]

Removes a PolygonMesh from screen, based on a given ID.

Parameters:
[in]idthe polygon object id (i.e., given on addPolygonMesh)
[in]viewportview port from where the PolygonMesh should be removed (default: all)

Definition at line 347 of file pcl_visualizer.h.

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.

Note:
This methods also removes PolygonMesh objects and PointClouds, if they match the ID
Parameters:
[in]idthe shape object id (i.e., given on addLine etc.)
[in]viewportview port from where the Point Cloud should be removed (default: all)

Definition at line 696 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::removeText3D ( const std::string id = "cloud",
int  viewport = 0 
)

Removes an added 3D text from the scene, based on a given ID.

Parameters:
[in]idthe 3D text id (i.e., given on addText3D etc.)
[in]viewportview port from where the 3D text should be removed (default: all)

Definition at line 736 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::renderView ( int  xres,
int  yres,
pcl::PointCloud< pcl::PointXYZ >::Ptr cloud 
)

Renders a virtual scene as seen from the camera viewpoint and returns the rendered point cloud. ATT: This method will only render the scene if only on viewport exists. Otherwise, returns an empty point cloud and exits immediately.

Parameters:
[in]xresis the size of the window (X) used to render the scene
[in]yresis the size of the window (Y) used to render the scene
[in]cloudis the rendered point cloud

Definition at line 3583 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( int  xres,
int  yres,
pcl::PointCloud< pcl::PointXYZ >::CloudVectorType &  cloud,
std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &  poses,
std::vector< float > &  enthropies,
int  tesselation_level,
float  view_angle = 45,
float  radius_sphere = 1,
bool  use_vertices = true 
)

The purpose of this method is to render a CAD model added to the visualizer from different viewpoints in order to simulate partial views of model. The viewpoint locations are the vertices of a tesselated sphere build from an icosaheadron. The tesselation paremeter controls how many times the triangles of the original icosahedron are divided to approximate the sphere and thus the number of partial view generated for a model, with a tesselation_level of 0, 12 views are generated if use_vertices=true and 20 views if use_vertices=false.

Parameters:
[in]xresthe size of the window (X) used to render the partial view of the object
[in]yresthe size of the window (Y) used to render the partial view of the object
[in]cloudis a vector of pointcloud with XYZ information that represent the model as seen from the respective viewpoints.
[out]posesrepresent the transformation from object coordinates to camera coordinates for the respective viewpoint.
[out]enthropiesare values between 0 and 1 representing which percentage of the model is seen from the respective viewpoint.
[in]tesselation_levelrepresents the number of subdivisions applied to the triangles of original icosahedron.
[in]view_anglefield of view of the virtual camera. Default: 45
[in]radius_spherethe tesselated sphere radius. Default: 1
[in]use_verticesif true, use the vertices of tesselated icosahedron (12,42,...) or if false, use the faces of tesselated icosahedron (20,80,...). Default: true

Definition at line 3141 of file pcl_visualizer.cpp.

Reset camera parameters and render.

Definition at line 1758 of file pcl_visualizer.cpp.

Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset.

Parameters:
[in]idthe point cloud object id (default: cloud)

Definition at line 1931 of file pcl_visualizer.cpp.

Set the stopped flag back to false.

Definition at line 4012 of file pcl_visualizer.cpp.

Save the current rendered image to disk, as a PNG screenshot.

Parameters:
[in]filethe name of the PNG file

Definition at line 376 of file pcl_visualizer.cpp.

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

Set the viewport's background color.

Parameters:
[in]rthe red component of the RGB color
[in]gthe green component of the RGB color
[in]bthe blue component of the RGB color
[in]viewportthe view port (default: all)

Definition at line 1240 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraClipDistances ( double  near,
double  far,
int  viewport = 0 
)

Set the camera clipping distances.

Parameters:
[in]nearthe near clipping distance (no objects closer than this to the camera will be drawn)
[in]farthe far clipping distance (no objects further away than this to the camera will be drawn)

Definition at line 1894 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraFieldOfView ( double  fovy,
int  viewport = 0 
)

Set the camera vertical field of view.

Parameters:
[in]fovyvertical field of view in radians
[in]viewportthe viewport to modify camera of (0 modifies all cameras)

Definition at line 1912 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraParameters ( const Eigen::Matrix3f &  intrinsics,
const Eigen::Matrix4f &  extrinsics,
int  viewport = 0 
)

Set the camera parameters via an intrinsics and and extrinsics matrix.

Note:
This assumes that the pixels are square and that the center of the image is at the center of the sensor.
Parameters:
[in]intrinsicsthe intrinsics that will be used to compute the VTK camera parameters
[in]extrinsicsthe extrinsics that will be used to compute the VTK camera parameters
[in]viewportthe viewport to modify camera of (0 modifies all cameras)

Definition at line 1819 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraParameters ( const Camera camera,
int  viewport = 0 
)

Set the camera parameters by given a full camera data structure.

Parameters:
[in]cameracamera structure containing all the camera parameters.
[in]viewportthe viewport to modify camera of (0 modifies all cameras)

Definition at line 1868 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraPosition ( double  pos_x,
double  pos_y,
double  pos_z,
double  view_x,
double  view_y,
double  view_z,
double  up_x,
double  up_y,
double  up_z,
int  viewport = 0 
)

Set the camera pose given by position, viewpoint and up vector.

Parameters:
[in]pos_xthe x coordinate of the camera location
[in]pos_ythe y coordinate of the camera location
[in]pos_zthe z coordinate of the camera location
[in]view_xthe x component of the view point of the camera
[in]view_ythe y component of the view point of the camera
[in]view_zthe z component of the view point of the camera
[in]up_xthe x component of the view up direction of the camera
[in]up_ythe y component of the view up direction of the camera
[in]up_zthe y component of the view up direction of the camera
[in]viewportthe viewport to modify camera of (0 modifies all cameras)

Definition at line 1770 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setCameraPosition ( double  pos_x,
double  pos_y,
double  pos_z,
double  up_x,
double  up_y,
double  up_z,
int  viewport = 0 
)

Set the camera location and viewup according to the given arguments.

Parameters:
[in]pos_xthe x coordinate of the camera location
[in]pos_ythe y coordinate of the camera location
[in]pos_zthe z coordinate of the camera location
[in]up_xthe x component of the view up direction of the camera
[in]up_ythe y component of the view up direction of the camera
[in]up_zthe z component of the view up direction of the camera
[in]viewportthe viewport to modify camera of (0 modifies all cameras)

Definition at line 1796 of file pcl_visualizer.cpp.

Enables/Disabled the underlying window mode to full screen.

Note:
This might or might not work, depending on your window manager. See the VTK documentation for additional details.
Parameters:
[in]modetrue for full screen, false otherwise

Definition at line 3912 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:
[in]propertythe property type
[in]val1the first value to be set
[in]val2the second value to be set
[in]val3the third value to be set
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud's rendering properties should be modified (default: all)

Definition at line 1265 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:
[in]propertythe property type
[in]valuethe value to be set
[in]idthe point cloud object id (default: cloud)
[in]viewportthe view port where the Point Cloud's rendering properties should be modified (default: all)

Definition at line 1340 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::setPointCloudSelected ( const bool  selected,
const std::string id = "cloud" 
)

Set whether the point cloud is selected or not.

Parameters:
[in]selectedwhether the cloud is selected or not (true = selected)
[in]idthe point cloud object id (default: cloud)

Definition at line 1396 of file pcl_visualizer.cpp.

Set the position in screen coordinates.

Parameters:
[in]xwhere to move the window to (X)
[in]ywhere to move the window to (Y)

Definition at line 3936 of file pcl_visualizer.cpp.

Changes the visual representation for all actors to points representation.

Definition at line 3094 of file pcl_visualizer.cpp.

Changes the visual representation for all actors to surface representation.

Definition at line 3075 of file pcl_visualizer.cpp.

Changes the visual representation for all actors to wireframe representation.

Definition at line 3113 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:
[in]propertythe property type
[in]valuethe value to be set
[in]idthe shape object id
[in]viewportthe view port where the shape's properties should be modified (default: all)

Definition at line 1471 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( int  property,
double  val1,
double  val2,
double  val3,
const std::string id,
int  viewport = 0 
)

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

Parameters:
[in]propertythe property type
[in]val1the first value to be set
[in]val2the second value to be set
[in]val3the third value to be set
[in]idthe shape object id
[in]viewportthe view port where the shape's properties should be modified (default: all)

Definition at line 1426 of file pcl_visualizer.cpp.

Sets whether the 2D overlay text showing the framerate of the window is displayed or not.

Parameters:
[in]show_fpsdetermines whether the fps text will be shown or not.

Definition at line 3133 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setSize ( int  xw,
int  yw 
)

Set the window size in screen coordinates.

Parameters:
[in]xwwindow size in horizontal (pixels)
[in]ywwindow size in vertical (pixels)

Definition at line 3944 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setupInteractor ( vtkRenderWindowInteractor *  iren,
vtkRenderWindow *  win 
)

Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object attached to a given vtkRenderWindow.

Parameters:
[in,out]irenthe vtkRenderWindowInteractor object to set up
[in,out]wina vtkRenderWindow object that the interactor is attached to

Definition at line 277 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::setupInteractor ( vtkRenderWindowInteractor *  iren,
vtkRenderWindow *  win,
vtkInteractorStyle *  style 
)

Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object attached to a given vtkRenderWindow.

Parameters:
[in,out]irenthe vtkRenderWindowInteractor object to set up
[in,out]wina vtkRenderWindow object that the interactor is attached to
[in,out]stylea vtkInteractorStyle object

Definition at line 320 of file pcl_visualizer.cpp.

Use Vertex Buffer Objects renderers.

Parameters:
[in]use_vbosset to true to use VBOs

Definition at line 4024 of file pcl_visualizer.cpp.

Enables or disable the underlying window borders.

Note:
This might or might not work, depending on your window manager. See the VTK documentation for additional details.
Parameters:
[in]modetrue for borders, false otherwise

Definition at line 3928 of file pcl_visualizer.cpp.

Set the visualizer window name.

Parameters:
[in]namethe name of the window

Definition at line 3920 of file pcl_visualizer.cpp.

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

Definition at line 425 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:
[in]time- How long (in ms) should the visualization loop be allowed to run.
[in]force_redraw- if false it might return without doing anything if the interactor's framerate does not require a redraw yet.

Definition at line 435 of file pcl_visualizer.cpp.

Update camera parameters and render.

Definition at line 1627 of file pcl_visualizer.cpp.

void pcl::visualization::PCLVisualizer::updateCells ( vtkSmartPointer< vtkIdTypeArray > &  cells,
vtkSmartPointer< vtkIdTypeArray > &  initcells,
vtkIdType  nr_points 
) [private]

Updates a set of cells (vtkIdTypeArray) if the number of points in a cloud changes.

Parameters:
[out]cellsthe vtkIdTypeArray object (set of cells) to update
[out]initcellsa previously saved set of cells. If the number of points in the current cloud is higher than the number of cells in cells, and initcells contains enough data, then a copy from it will be made instead of regenerating the entire array.
[in]nr_pointsthe number of points in the new cloud. This dictates how many cells we need to generate

Definition at line 3723 of file pcl_visualizer.cpp.

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

Parameters:
[in]idthe point cloud object id
[in]indexthe color handler index to use

Definition at line 2729 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updateCorrespondences ( const typename pcl::PointCloud< PointT >::ConstPtr source_points,
const typename pcl::PointCloud< PointT >::ConstPtr target_points,
const pcl::Correspondences correspondences,
int  nth,
const std::string id = "correspondences" 
)

Update the specified correspondences to the display.

Parameters:
[in]source_pointsThe source points
[in]target_pointsThe target points
[in]correspondencesThe mapping from source points to target points. Each element must be an index into target_points
[in]nthdisplay only the Nth correspondence (e.g., skip the rest)
[in]idthe polygon object id (default: "correspondences")

Definition at line 1095 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updatePointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const std::string id = "cloud" 
)

Updates the XYZ data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 1385 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updatePointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const PointCloudGeometryHandler< PointT > &  geometry_handler,
const std::string id = "cloud" 
)

Updates the XYZ data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]geometry_handlerthe geometry handler to use
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 1416 of file pcl_visualizer.hpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updatePointCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const PointCloudColorHandler< PointT > &  color_handler,
const std::string id = "cloud" 
)

Updates the XYZ data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]color_handlerthe color handler to use
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 1450 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::updatePointCloud ( const pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud,
const std::string id = "cloud" 
) [inline]

Updates the XYZ data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 807 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::updatePointCloud ( const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr cloud,
const std::string id = "cloud" 
) [inline]

Updates the XYZRGB data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 819 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::updatePointCloud ( const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr cloud,
const std::string id = "cloud" 
) [inline]

Updates the XYZRGBA data for an existing cloud object id on screen.

Parameters:
[in]cloudthe input point cloud dataset
[in]idthe point cloud object id to update (default: cloud)
Returns:
false if no cloud with the specified ID was found

Definition at line 832 of file pcl_visualizer.h.

bool pcl::visualization::PCLVisualizer::updatePointCloudPose ( const std::string id,
const Eigen::Affine3f &  pose 
)

Set the pose of an existing point cloud.

Returns false if the point cloud doesn't exist, true if the pose was succesfully updated.

Parameters:
[in]idthe point cloud object id (i.e., given on addPointCloud etc.)
[in]posethe new pose
Returns:
false if no point cloud with the specified ID was found

Definition at line 1662 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updatePolygonMesh ( const typename pcl::PointCloud< PointT >::ConstPtr cloud,
const std::vector< pcl::Vertices > &  vertices,
const std::string id = "polygon" 
)

Update a PolygonMesh object on screen.

Parameters:
[in]cloudthe polygonal mesh point cloud
[in]verticesthe polygonal mesh vertices
[in]idthe polygon object id (default: "polygon")
Returns:
false if no polygonmesh with the specified ID was found

Definition at line 1698 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::updatePolygonMesh ( const pcl::PolygonMesh polymesh,
const std::string id = "polygon" 
)

Update a PolygonMesh object on screen.

Parameters:
[in]polymeshthe polygonal mesh
[in]idthe polygon object id (default: "polygon")
Returns:
false if no polygonmesh with the specified ID was found

Definition at line 2906 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::updateShapePose ( const std::string id,
const Eigen::Affine3f &  pose 
)

Set the pose of an existing shape.

Returns false if the shape doesn't exist, true if the pose was succesfully updated.

Parameters:
[in]idthe shape or cloud object id (i.e., given on addLine etc.)
[in]posethe new pose
Returns:
false if no shape or cloud with the specified ID was found

Definition at line 1639 of file pcl_visualizer.cpp.

template<typename PointT >
bool pcl::visualization::PCLVisualizer::updateSphere ( const PointT center,
double  radius,
double  r,
double  g,
double  b,
const std::string id = "sphere" 
)

Update an existing sphere shape from a point and a radius.

Parameters:
[in]centerthe center of the sphere
[in]radiusthe radius of the sphere
[in]rthe red channel of the color that the sphere should be rendered with
[in]gthe green channel of the color that the sphere should be rendered with
[in]bthe blue channel of the color that the sphere should be rendered with
[in]idthe sphere id/name (default: "sphere")

Definition at line 606 of file pcl_visualizer.hpp.

bool pcl::visualization::PCLVisualizer::updateText ( const std::string text,
int  xpos,
int  ypos,
const std::string id = "" 
)

Update a text to screen.

Parameters:
[in]textthe text to update
[in]xposthe new X position on screen
[in]yposthe new Y position on screen
[in]idthe text object id (default: equal to the "text" parameter)

Definition at line 2647 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::updateText ( const std::string text,
int  xpos,
int  ypos,
double  r,
double  g,
double  b,
const std::string id = "" 
)

Update a text to screen.

Parameters:
[in]textthe text to update
[in]xposthe new X position on screen
[in]yposthe new Y position on screen
[in]rthe red color value
[in]gthe green color value
[in]bthe blue color vlaue
[in]idthe text object id (default: equal to the "text" parameter)

Definition at line 2672 of file pcl_visualizer.cpp.

bool pcl::visualization::PCLVisualizer::updateText ( const std::string text,
int  xpos,
int  ypos,
int  fontsize,
double  r,
double  g,
double  b,
const std::string id = "" 
)

Update a text to screen.

Parameters:
[in]textthe text to update
[in]xposthe new X position on screen
[in]yposthe new Y position on screen
[in]fontsizethe fontsize of the text
[in]rthe red color value
[in]gthe green color value
[in]bthe blue color vlaue
[in]idthe text object id (default: equal to the "text" parameter)

Definition at line 2699 of file pcl_visualizer.cpp.

Returns true when the user tried to close the window.

Definition at line 3998 of file pcl_visualizer.cpp.


Member Data Documentation

vtkSmartPointer<vtkOrientationMarkerWidget> pcl::visualization::PCLVisualizer::axes_widget_ [private]

Internal pointer to widget which contains a set of axes.

Definition at line 1763 of file pcl_visualizer.h.

Boolean that holds whether or not the camera parameters were manually initialized.

Definition at line 1766 of file pcl_visualizer.h.

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

Definition at line 1754 of file pcl_visualizer.h.

Internal list with actor pointers and viewpoint for coordinates.

Definition at line 1760 of file pcl_visualizer.h.

Definition at line 1742 of file pcl_visualizer.h.

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

Definition at line 1741 of file pcl_visualizer.h.

vtkSmartPointer<vtkRenderWindowInteractor> pcl::visualization::PCLVisualizer::interactor_ [protected]

The render window interactor.

Definition at line 1685 of file pcl_visualizer.h.

vtkSmartPointer<vtkRendererCollection> pcl::visualization::PCLVisualizer::rens_ [private]

The collection of renderers used.

Definition at line 1745 of file pcl_visualizer.h.

Internal list with actor pointers and name IDs for shapes.

Definition at line 1757 of file pcl_visualizer.h.

Set to false if the interaction loop is running.

Definition at line 1735 of file pcl_visualizer.h.

The render window interactor style.

Definition at line 1751 of file pcl_visualizer.h.

Global timer ID. Used in destructor only.

Definition at line 1738 of file pcl_visualizer.h.

The FPSCallback object for the current visualizer.

Definition at line 1731 of file pcl_visualizer.h.

Boolean that holds whether or not to use the vtkVertexBufferObjectMapper.

Definition at line 1769 of file pcl_visualizer.h.

vtkSmartPointer<vtkRenderWindow> pcl::visualization::PCLVisualizer::win_ [private]

The render window.

Definition at line 1748 of file pcl_visualizer.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:47:19