PCL Visualizer main class. More...
#include <pcl_visualizer.h>
Classes | |
struct | ExitCallback |
struct | ExitMainLoopTimerCallback |
Public Types | |
typedef PointCloudColorHandler < sensor_msgs::PointCloud2 > | ColorHandler |
typedef ColorHandler::ConstPtr | ColorHandlerConstPtr |
typedef ColorHandler::Ptr | ColorHandlerPtr |
typedef PointCloudGeometryHandler < sensor_msgs::PointCloud2 > | GeometryHandler |
typedef GeometryHandler::ConstPtr | GeometryHandlerConstPtr |
typedef GeometryHandler::Ptr | GeometryHandlerPtr |
Public Member Functions | |
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. | |
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, 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 (double x_min, double x_max, double y_min, double y_max, double z_min, double 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 from a set of bounding points. | |
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. | |
bool | addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id="plane", int viewport=0) |
Add a plane from a set of given model coefficients. | |
template<typename PointT > | |
bool | addPointCloud (const 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 sensor_msgs::PointCloud2::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 sensor_msgs::PointCloud2::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 sensor_msgs::PointCloud2::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 PointNT > | |
bool | addPointCloudNormals (const typename pcl::PointCloud< PointNT >::ConstPtr &cloud, int level=100, double scale=0.02, const std::string &id="cloud", int viewport=0) |
Add the estimated surface normals of a Point Cloud to screen. | |
template<typename PointT , typename PointNT > | |
bool | addPointCloudNormals (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const typename pcl::PointCloud< PointNT >::ConstPtr &normals, int level=100, double scale=0.02, const std::string &id="cloud", int viewport=0) |
Add the estimated surface normals of a Point Cloud to screen. | |
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, double scale=1.0, const std::string &id="cloud", int viewport=0) |
Add the estimated principal curvatures of a Point Cloud to screen. | |
template<typename PointT > | |
bool | addPolygon (const 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) | |
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 ¢er, 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 ¢er, 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]. | |
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. | |
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< vtkRenderWindow > | getRenderWindow () |
Return a pointer to the underlying VTK Render Window used. | |
Eigen::Affine3f | getViewerPose () |
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 | 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. | |
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, std::vector< pcl::PointCloud< pcl::PointXYZ >, Eigen::aligned_allocator< pcl::PointCloud< pcl::PointXYZ > > > &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 | setCameraPose (double posX, double posY, double posZ, double viewX, double viewY, double viewZ, double upX, double upY, double upZ, int viewport=0) |
sets the camera pose given by position, viewpoint and up vector | |
void | setCameraPosition (double posX, double posY, double posZ, double viewX, double viewY, double viewZ, 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. | |
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 | setupInteractor (vtkRenderWindowInteractor *iren, vtkRenderWindow *win) |
Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object attached to a given vtkRenderWindow. | |
void | setWindowBorders (bool mode) |
Enables or disable the underlying window borders. | |
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 | 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. | |
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 | updateShapePose (const std::string &id, const Eigen::Affine3f &pose) |
Set the pose of an existing shape. | |
template<typename PointT > | |
bool | updateSphere (const PointT ¢er, 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. | |
Public Attributes | |
Camera | camera_ |
Camera view, window position and size. | |
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 | convertToVtkMatrix (const Eigen::Matrix4f &m, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix) |
Convert Eigen::Matrix4f to vtkMatrix4x4. | |
void | convertToVtkMatrix (const Eigen::Vector4f &origin, const Eigen::Quaternion< float > &orientation, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix) |
Convert origin and orientation to vtkMatrix4x4. | |
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< 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 | |
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< ExitCallback > | exit_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< vtkRenderWindow > | win_ |
The render window. |
PCL Visualizer main class.
Definition at line 85 of file pcl_visualizer.h.
typedef PointCloudColorHandler<sensor_msgs::PointCloud2> pcl::visualization::PCLVisualizer::ColorHandler |
Definition at line 92 of file pcl_visualizer.h.
Definition at line 94 of file pcl_visualizer.h.
Definition at line 93 of file pcl_visualizer.h.
typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2> pcl::visualization::PCLVisualizer::GeometryHandler |
Definition at line 88 of file pcl_visualizer.h.
Definition at line 90 of file pcl_visualizer.h.
Definition at line 89 of file pcl_visualizer.h.
pcl::visualization::PCLVisualizer::PCLVisualizer | ( | const std::string & | name = "" , |
const bool | create_interactor = true |
||
) |
PCL Visualizer constructor.
[in] | name | the window name (empty by default) |
[in] | create_interactor | if true (default), create an interactor, false otherwise |
Definition at line 55 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.
[in] | argc | |
[in] | argv | |
[in] | name | the window name (empty by default) |
[in] | style | interactor style (defaults to PCLVisualizerInteractorStyle) |
[in] | create_interactor | if true (default), create an interactor, false otherwise |
Definition at line 101 of file pcl_visualizer.cpp.
pcl::visualization::PCLVisualizer::~PCLVisualizer | ( | ) | [virtual] |
PCL Visualizer destructor.
Definition at line 249 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::addActorToRenderer | ( | const vtkSmartPointer< vtkProp > & | actor, |
int | viewport = 0 |
||
) | [private] |
Internal method. Adds a vtk actor to screen.
[in] | actor | a pointer to the vtk actor object |
[in] | viewport | the view port where the actor should be added to (default: all) |
Definition at line 754 of file pcl_visualizer.cpp.
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.
[in] | pt1 | the first (start) point on the line |
[in] | pt2 | the second (end) point on the line |
[in] | r | the red channel of the color that the line should be rendered with |
[in] | g | the green channel of the color that the line should be rendered with |
[in] | b | the blue channel of the color that the line should be rendered with |
[in] | id | the arrow id/name (default: "arrow") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 364 of file pcl_visualizer.hpp.
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.
[in] | pt1 | the first (start) point on the line |
[in] | pt2 | the second (end) point on the line |
[in] | r | the red channel of the color that the line should be rendered with |
[in] | g | the green channel of the color that the line should be rendered with |
[in] | b | the blue channel of the color that the line should be rendered with |
[in] | display_length | true if the length should be displayed on the arrow as text |
[in] | id | the line id/name (default: "arrow") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 393 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.
[in] | coefficients | the model coefficients (x, y, radius) |
[in] | id | the 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 1868 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.
[in] | coefficients | the model coefficients (point_on_axis, axis_direction, radiu) |
[in] | id | the cone id/name (default: "cone") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1893 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.
[in] | scale | the scale of the axes (default: 1) |
[in] | viewport | the view port where the 3D axes should be added (default: all) |
Definition at line 320 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.
[in] | scale | the scale of the axes (default: 1) |
[in] | x | the X position of the axes |
[in] | y | the Y position of the axes |
[in] | z | the Z position of the axes |
[in] | viewport | the view port where the 3D axes should be added (default: all) |
Definition at line 359 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.
[in] | scale | the scale of the axes (default: 1) |
[in] | t | transformation matrix |
[in] | viewport | the 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 399 of file pcl_visualizer.cpp.
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.
[in] | source_points | The source points |
[in] | target_points | The target points |
[in] | correspondences | The mapping from source points to target points. Each element must be an index into target_points |
[in] | id | the polygon object id (default: "correspondences") |
[in] | viewport | the view port where the correspondences should be added (default: all) |
Definition at line 699 of file pcl_visualizer.hpp.
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 |
||
) |
Add the specified correspondences to the display.
[in] | source_points | The source points |
[in] | target_points | The target points |
[in] | correspondences | The mapping from source points to target points. Each element must be an index into target_points |
[in] | id | the polygon object id (default: "correspondences") |
[in] | viewport | the view port where the correspondences should be added (default: all) |
Definition at line 758 of file pcl_visualizer.hpp.
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.
[in] | coefficients | the model coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth) |
[in] | id | the cube id/name (default: "cube") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1586 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.
[in] | translation | a translation to apply to the cube from 0,0,0 |
[in] | rotation | a quaternion-based rotation to apply to the cube |
[in] | width | the cube's width |
[in] | height | the cube's height |
[in] | depth | the cube's depth |
[in] | id | the cube id/name (default: "cube") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1612 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::addCube | ( | double | x_min, |
double | x_max, | ||
double | y_min, | ||
double | y_max, | ||
double | z_min, | ||
double | 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 from a set of bounding points.
[in] | x_min | is the minimum x value of the box |
[in] | x_max | is the maximum x value of the box |
[in] | y_min | is the minimum y value of the box |
[in] | y_max | is the maximum y value of the box |
[in] | z_min | is the minimum z value of the box |
[in] | z_max | is the maximum z value of the box |
[in] | r | the red color value (default: 1.0) |
[in] | g | the green color value (default: 1.0) |
[in] | b | the blue color vlaue (default: 1.0) |
[in] | id | the cube id/name (default: "cube") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1640 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.
[in] | coefficients | the model coefficients (point_on_axis, axis_direction, radius) |
[in] | id | the 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 1560 of file pcl_visualizer.cpp.
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.
[in] | pt1 | the first (start) point on the line |
[in] | pt2 | the second (end) point on the line |
[in] | id | the line id/name (default: "line") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 426 of file pcl_visualizer.hpp.
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.
[in] | pt1 | the first (start) point on the line |
[in] | pt2 | the second (end) point on the line |
[in] | r | the red channel of the color that the line should be rendered with |
[in] | g | the green channel of the color that the line should be rendered with |
[in] | b | the blue channel of the color that the line should be rendered with |
[in] | id | the line id/name (default: "line") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 337 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.
[in] | coefficients | the model coefficients (point_on_line, direction) |
[in] | id | the 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 1813 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.
[in] | filename | of the ply file |
[in] | id | the model id/name (default: "PLYModel") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1751 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.
[in] | filename | of the ply file |
[in] | transform | transformation to apply |
[in] | id | the model id/name (default: "PLYModel") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1779 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.
[in] | polydata | vtkPolyData |
[in] | id | the model id/name (default: "PolyData") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1696 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.
[in] | polydata | vtkPolyData |
[in] | transform | transformation to apply |
[in] | id | the model id/name (default: "PolyData") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1720 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.
[in] | coefficients | the model coefficients (a, b, c, d with ax+by+cz+d=0) |
[in] | id | the 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);
coefficients | the model coefficients (a, b, c, d with ax+by+cz+d=0) |
id | the plane id/name (default: "plane") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 1843 of file pcl_visualizer.cpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 54 of file pcl_visualizer.hpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | use a geometry handler object to extract the XYZ data |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 65 of file pcl_visualizer.hpp.
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).
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | use a geometry handler object to extract the XYZ data |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 86 of file pcl_visualizer.hpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 109 of file pcl_visualizer.hpp.
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).
[in] | cloud | the input point cloud dataset |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 134 of file pcl_visualizer.hpp.
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).
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | a specific PointCloud visualizer handler for geometry |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 155 of file pcl_visualizer.hpp.
bool pcl::visualization::PCLVisualizer::addPointCloud | ( | const sensor_msgs::PointCloud2::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).
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | a specific PointCloud visualizer handler for geometry |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 3085 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::addPointCloud | ( | const sensor_msgs::PointCloud2::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).
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | a specific PointCloud visualizer handler for geometry |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 3108 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::addPointCloud | ( | const sensor_msgs::PointCloud2::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).
[in] | cloud | the input point cloud dataset |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 3132 of file pcl_visualizer.cpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | color_handler | a specific PointCloud visualizer handler for colors |
[in] | geometry_handler | use a geometry handler object to extract the XYZ data |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 176 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 711 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 724 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 737 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::addPointCloudNormals | ( | const typename pcl::PointCloud< PointNT >::ConstPtr & | cloud, |
int | level = 100 , |
||
double | scale = 0.02 , |
||
const std::string & | id = "cloud" , |
||
int | viewport = 0 |
||
) |
Add the estimated surface normals of a Point Cloud to screen.
[in] | cloud | the input point cloud dataset containing XYZ data and normals |
[in] | level | display only every level'th point (default: 100) |
[in] | scale | the normal arrow scale (default: 0.02m) |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 615 of file pcl_visualizer.hpp.
bool pcl::visualization::PCLVisualizer::addPointCloudNormals | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloud, |
const typename pcl::PointCloud< PointNT >::ConstPtr & | normals, | ||
int | level = 100 , |
||
double | scale = 0.02 , |
||
const std::string & | id = "cloud" , |
||
int | viewport = 0 |
||
) |
Add the estimated surface normals of a Point Cloud to screen.
[in] | cloud | the input point cloud dataset containing the XYZ data |
[in] | normals | the input point cloud dataset containing the normal data |
[in] | level | display only every level'th point (default: 100) |
[in] | scale | the normal arrow scale (default: 0.02m) |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 624 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 , |
||
double | scale = 1.0 , |
||
const std::string & | id = "cloud" , |
||
int | viewport = 0 |
||
) |
Add the estimated principal curvatures of a Point Cloud to screen.
[in] | cloud | the input point cloud dataset containing the XYZ data |
[in] | normals | the input point cloud dataset containing the normal data |
[in] | pcs | the input point cloud dataset containing the principal curvatures data |
[in] | level | display only every level'th point. Default: 100 |
[in] | scale | the normal arrow scale. Default: 1.0 |
[in] | id | the point cloud object id. Default: "cloud" |
[in] | viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 611 of file pcl_visualizer.cpp.
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)
[in] | cloud | the point cloud dataset representing the polygon |
[in] | r | the red channel of the color that the polygon should be rendered with |
[in] | g | the green channel of the color that the polygon should be rendered with |
[in] | b | the 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 298 of file pcl_visualizer.hpp.
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)
[in] | cloud | the point cloud dataset representing the polygon |
[in] | id | the polygon id/name (default: "polygon") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 327 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.
[in] | polymesh | the polygonal mesh |
[in] | id | the polygon object id (default: "polygon") |
[in] | viewport | the view port where the PolygonMesh should be added (default: all) |
Definition at line 2176 of file pcl_visualizer.cpp.
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.
[in] | cloud | the polygonal mesh point cloud |
[in] | vertices | the polygonal mesh vertices |
[in] | id | the polygon object id (default: "polygon") |
[in] | viewport | the view port where the PolygonMesh should be added (default: all) |
Definition at line 1125 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.
[in] | polymesh | the polygonal mesh from where the polylines will be extracted |
[in] | id | the polygon object id (default: "polygon") |
[in] | viewport | the view port where the PolygonMesh should be added (default: all) |
Definition at line 2287 of file pcl_visualizer.cpp.
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.
[in] | center | the center of the sphere |
[in] | radius | the radius of the sphere |
[in] | id | the sphere id/name (default: "sphere") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 518 of file pcl_visualizer.hpp.
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.
[in] | center | the center of the sphere |
[in] | radius | the radius of the sphere |
[in] | r | the red channel of the color that the sphere should be rendered with |
[in] | g | the green channel of the color that the sphere should be rendered with |
[in] | b | the blue channel of the color that the sphere should be rendered with |
[in] | id | the line id/name (default: "sphere") |
[in] | viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 478 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.
[in] | coefficients | the model coefficients (sphere center, radius) |
[in] | id | the 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 1670 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.
[in] | text | the text to add |
[in] | xpos | the X position on screen where the text should be added |
[in] | ypos | the Y position on screen where the text should be added |
[in] | id | the text object id (default: equal to the "text" parameter) |
[in] | viewport | the view port (default: all) |
Definition at line 1942 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.
[in] | text | the text to add |
[in] | xpos | the X position on screen where the text should be added |
[in] | ypos | the Y position on screen where the text should be added |
[in] | r | the red color value |
[in] | g | the green color value |
[in] | b | the blue color vlaue |
[in] | id | the text object id (default: equal to the "text" parameter) |
[in] | viewport | the view port (default: all) |
Definition at line 1978 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.
[in] | text | the text to add |
[in] | xpos | the X position on screen where the text should be added |
[in] | ypos | the Y position on screen where the text should be added |
[in] | fontsize | the fontsize of the text |
[in] | r | the red color value |
[in] | g | the green color value |
[in] | b | the blue color vlaue |
[in] | id | the text object id (default: equal to the "text" parameter) |
[in] | viewport | the view port (default: all) |
Definition at line 2014 of file pcl_visualizer.cpp.
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.
[in] | text | the text to add |
[in] | position | the world position where the text should be added |
[in] | textScale | the scale of the text to render |
[in] | r | the red color value |
[in] | g | the green color value |
[in] | b | the blue color value |
[in] | id | the text object id (default: equal to the "text" parameter) |
[in] | viewport | the view port (default: all) |
Definition at line 549 of file pcl_visualizer.hpp.
void pcl::visualization::PCLVisualizer::allocVtkPolyData | ( | vtkSmartPointer< vtkAppendPolyData > & | polydata | ) | [private] |
Allocate a new polydata smartpointer. Internal.
[out] | polydata | the resultant poly data |
Definition at line 3023 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::allocVtkPolyData | ( | vtkSmartPointer< vtkPolyData > & | polydata | ) | [private] |
Allocate a new polydata smartpointer. Internal.
[out] | polydata | the resultant poly data |
Definition at line 3029 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::allocVtkUnstructuredGrid | ( | vtkSmartPointer< vtkUnstructuredGrid > & | polydata | ) | [private] |
Allocate a new unstructured grid smartpointer. Internal.
[out] | polydata | the resultant poly data |
Definition at line 3035 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::cameraParamsSet | ( | ) | const |
Checks whether the camera parameters were manually loaded from file.
Definition at line 1180 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::close | ( | ) | [inline] |
Stop the interaction and close the visualizaton window.
Definition at line 969 of file pcl_visualizer.h.
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.
[in] | cloud | the input PCL PointCloud dataset |
[out] | polydata | the resultant polydata containing the cloud |
[out] | initcells | a 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 200 of file pcl_visualizer.hpp.
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.
[in] | geometry_handler | the geometry handler object used to extract the XYZ data |
[out] | polydata | the resultant polydata containing the cloud |
[out] | initcells | a 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 265 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.
[in] | geometry_handler | the geometry handler object used to extract the XYZ data |
[out] | polydata | the resultant polydata containing the cloud |
[out] | initcells | a 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 859 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::convertToVtkMatrix | ( | const Eigen::Matrix4f & | m, |
vtkSmartPointer< vtkMatrix4x4 > & | vtk_matrix | ||
) | [private] |
Convert Eigen::Matrix4f to vtkMatrix4x4.
[in] | m | the input Eigen matrix |
[out] | vtk_matrix | the resultant VTK matrix |
Definition at line 3074 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::convertToVtkMatrix | ( | const Eigen::Vector4f & | origin, |
const Eigen::Quaternion< float > & | orientation, | ||
vtkSmartPointer< vtkMatrix4x4 > & | vtk_matrix | ||
) | [private] |
Convert origin and orientation to vtkMatrix4x4.
[in] | origin | the point cloud origin |
[in] | orientation | the point cloud orientation |
[out] | vtk_matrix | the resultant VTK 4x4 matrix |
Definition at line 3054 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.
[in] | data | the vtk polydata object to create an actor for |
[out] | actor | the resultant vtk actor object |
[in] | use_scalars | set 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
Definition at line 819 of file pcl_visualizer.cpp.
Create the internal Interactor object.
Definition at line 159 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].
[in] | xmin | the minimum X coordinate for the viewport (0.0 <= 1.0) |
[in] | ymin | the minimum Y coordinate for the viewport (0.0 <= 1.0) |
[in] | xmax | the maximum X coordinate for the viewport (0.0 <= 1.0) |
[in] | ymax | the maximum Y coordinate for the viewport (0.0 <= 1.0) |
[in] | viewport | the id of the new viewport |
Definition at line 1918 of file pcl_visualizer.cpp.
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.
[in] | geometry_handler | the geometric handler that contains the XYZ data |
[in] | color_handler | the color handler that contains the "RGB" (scalar) data |
[in] | id | the point cloud object id |
[in] | viewport | the view port where the Point Cloud should be added |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
Definition at line 817 of file pcl_visualizer.hpp.
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.
[in] | geometry_handler | the geometric handler that contains the XYZ data |
[in] | color_handler | the color handler that contains the "RGB" (scalar) data |
[in] | id | the point cloud object id |
[in] | viewport | the view port where the Point Cloud should be added |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
Definition at line 873 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.
[in] | geometry_handler | the geometric handler that contains the XYZ data |
[in] | color_handler | the color handler that contains the "RGB" (scalar) data |
[in] | id | the point cloud object id |
[in] | viewport | the view port where the Point Cloud should be added |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
Definition at line 2919 of file pcl_visualizer.cpp.
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.
[in] | geometry_handler | the geometric handler that contains the XYZ data |
[in] | color_handler | the color handler that contains the "RGB" (scalar) data |
[in] | id | the point cloud object id |
[in] | viewport | the view port where the Point Cloud should be added |
[in] | sensor_origin | the origin of the cloud data in global coordinates (defaults to 0,0,0) |
[in] | sensor_orientation | the orientation of the cloud data in global coordinates (defaults to 1,0,0,0) |
Definition at line 931 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.
[in] | argc | |
[in] | argv |
Definition at line 1432 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::getCameras | ( | std::vector< Camera > & | cameras | ) |
Get the current camera parameters.
Definition at line 1226 of file pcl_visualizer.cpp.
int pcl::visualization::PCLVisualizer::getColorHandlerIndex | ( | const std::string & | id | ) | [inline] |
Get the color handler index of a rendered PointCloud based on its ID.
[in] | id | the point cloud object id |
Definition at line 867 of file pcl_visualizer.h.
int pcl::visualization::PCLVisualizer::getGeometryHandlerIndex | ( | const std::string & | id | ) | [inline] |
Get the geometry handler index of a rendered PointCloud based on its ID.
[in] | id | the point cloud object id |
Definition at line 880 of file pcl_visualizer.h.
vtkSmartPointer<PCLVisualizerInteractorStyle> pcl::visualization::PCLVisualizer::getInteractorStyle | ( | ) | [inline] |
Get a pointer to the current interactor style used.
Definition at line 1485 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.
[in] | property | the property type |
[in] | value | the resultant property value |
[in] | id | the point cloud object id (default: cloud) |
Definition at line 952 of file pcl_visualizer.cpp.
vtkSmartPointer<vtkRenderWindow> pcl::visualization::PCLVisualizer::getRenderWindow | ( | ) | [inline] |
Return a pointer to the underlying VTK Render Window used.
Definition at line 1465 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.
[in] | origin | the camera origin |
[in] | orientation | the camera orientation |
[out] | transformation | the camera transformation matrix |
Definition at line 3042 of file pcl_visualizer.cpp.
Eigen::Affine3f pcl::visualization::PCLVisualizer::getViewerPose | ( | ) |
Get the current viewing pose.
Definition at line 1255 of file pcl_visualizer.cpp.
Initialize camera parameters with some default values.
Definition at line 1169 of file pcl_visualizer.cpp.
boost::signals2::connection pcl::visualization::PCLVisualizer::registerKeyboardCallback | ( | boost::function< void(const pcl::visualization::KeyboardEvent &)> | cb | ) |
Register a callback boost::function for keyboard events.
[in] | cb | a boost function that will be registered as a callback for a keyboard event |
Definition at line 270 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.
[in] | callback | the function that will be registered as a callback for a keyboard event |
[in] | cookie | user data that is passed to the callback |
Definition at line 151 of file pcl_visualizer.h.
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.
[in] | callback | the member function that will be registered as a callback for a keyboard event |
[in] | instance | instance to the class that implements the callback function |
[in] | cookie | user data that is passed to the callback |
Definition at line 163 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.
[in] | cb | a boost function that will be registered as a callback for a mouse event |
Definition at line 277 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.
[in] | callback | the function that will be registered as a callback for a mouse event |
[in] | cookie | user data that is passed to the callback |
Definition at line 181 of file pcl_visualizer.h.
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.
[in] | callback | the member function that will be registered as a callback for a mouse event |
[in] | instance | instance to the class that implements the callback function |
[in] | cookie | user data that is passed to the callback |
Definition at line 193 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.
[in] | cb | a boost function that will be registered as a callback for a point picking event |
Definition at line 284 of file pcl_visualizer.cpp.
boost::signals2::connection pcl::visualization::PCLVisualizer::registerPointPickingCallback | ( | void(*)(const pcl::visualization::PointPickingEvent &, void *) | callback, |
void * | cookie = NULL |
||
) | [inline] |
Register a callback function for point picking events.
[in] | callback | the function that will be registered as a callback for a point picking event |
[in] | cookie | user data that is passed to the callback |
Definition at line 211 of file pcl_visualizer.h.
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.
[in] | callback | the member function that will be registered as a callback for a point picking event |
[in] | instance | instance to the class that implements the callback function |
[in] | cookie | user data that is passed to the callback |
Definition at line 223 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.
[in] | actor | a pointer to the vtk actor object |
[in] | viewport | the view port where the actor should be removed from (default: all) |
Definition at line 714 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.
[in] | actor | a pointer to the vtk actor object |
[in] | viewport | the view port where the actor should be added to (default: all) |
Definition at line 779 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::removeAllPointClouds | ( | int | viewport = 0 | ) |
Remove all point cloud data on screen from the given viewport.
[in] | viewport | view port from where the clouds should be removed (default: all) |
Definition at line 579 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::removeAllShapes | ( | int | viewport = 0 | ) |
Remove all 3D shape data on screen from the given viewport.
[in] | viewport | view port from where the shapes should be removed (default: all) |
Definition at line 595 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::removeCoordinateSystem | ( | int | viewport = 0 | ) |
Removes a previously added 3D axes (coordinate system)
[in] | viewport | view port where the 3D axes should be removed from (default: all) |
Definition at line 476 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::removeCorrespondences | ( | const std::string & | id = "correspondences" , |
int | viewport = 0 |
||
) | [inline] |
Remove the specified correspondences from the display.
[in] | id | the polygon correspondences object id (i.e., given on addCorrespondences) |
[in] | viewport | view port from where the correspondences should be removed (default: all) |
Definition at line 858 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::removePointCloud | ( | const std::string & | id = "cloud" , |
int | viewport = 0 |
||
) |
Removes a Point Cloud from screen, based on a given ID.
[in] | id | the point cloud object id (i.e., given on addPointCloud) |
[in] | viewport | view port from where the Point Cloud should be removed (default: all) |
Definition at line 496 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.
[in] | id | the polygon object id (i.e., given on addPolygonMesh) |
[in] | viewport | view port from where the PolygonMesh should be removed (default: all) |
Definition at line 311 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.
[in] | id | the shape object id (i.e., given on addLine etc.) |
[in] | viewport | view port from where the Point Cloud should be removed (default: all) |
Definition at line 516 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.
[in] | id | the 3D text id (i.e., given on addText3D etc.) |
[in] | viewport | view port from where the 3D text should be removed (default: all) |
Definition at line 556 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.
[in] | xres | is the size of the window (X) used to render the scene |
[in] | yres | is the size of the window (Y) used to render the scene |
[in] | cloud | is the rendered point cloud |
Definition at line 2845 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::renderViewTesselatedSphere | ( | int | xres, |
int | yres, | ||
std::vector< pcl::PointCloud< pcl::PointXYZ >, Eigen::aligned_allocator< pcl::PointCloud< pcl::PointXYZ > > > & | 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.
[in] | xres | the size of the window (X) used to render the partial view of the object |
[in] | yres | the size of the window (Y) used to render the partial view of the object |
[in] | cloud | is a vector of pointcloud with XYZ information that represent the model as seen from the respective viewpoints. |
[out] | poses | represent the transformation from object coordinates to camera coordinates for the respective viewpoint. |
[out] | enthropies | are values between 0 and 1 representing which percentage of the model is seen from the respective viewpoint. |
[in] | tesselation_level | represents the number of subdivisions applied to the triangles of original icosahedron. |
[in] | view_angle | field of view of the virtual camera. Default: 45 |
[in] | radius_sphere | the tesselated sphere radius. Default: 1 |
[in] | use_vertices | if 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 2407 of file pcl_visualizer.cpp.
Reset camera parameters and render.
Definition at line 1275 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::resetCameraViewpoint | ( | const std::string & | id = "cloud" | ) |
Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset.
[in] | id | the point cloud object id (default: cloud) |
Definition at line 1337 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::resetStoppedFlag | ( | ) | [inline] |
Set the stopped flag back to false.
Definition at line 964 of file pcl_visualizer.h.
void pcl::visualization::PCLVisualizer::saveScreenshot | ( | const std::string & | file | ) |
Save the current rendered image to disk, as a PNG screenshot.
[in] | file | the name of the PNG file |
Definition at line 263 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.
[in] | r | the red component of the RGB color |
[in] | g | the green component of the RGB color |
[in] | b | the blue component of the RGB color |
[in] | viewport | the view port (default: all) |
Definition at line 893 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::setCameraPose | ( | double | posX, |
double | posY, | ||
double | posZ, | ||
double | viewX, | ||
double | viewY, | ||
double | viewZ, | ||
double | upX, | ||
double | upY, | ||
double | upZ, | ||
int | viewport = 0 |
||
) |
sets the camera pose given by position, viewpoint and up vector
posX | the x co-ordinate of the camera location |
posY | the y co-ordinate of the camera location |
posZ | the z co-ordinate of the camera location |
viewX | the x component of the view upoint of the camera |
viewY | the y component of the view point of the camera |
viewZ | the z component of the view point of the camera |
upX | the x component of the view up direction of the camera |
upY | the y component of the view up direction of the camera |
upZ | the y component of the view up direction of the camera |
viewport | the viewport to modify camera of, if 0, modifies all cameras |
Definition at line 1289 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::setCameraPosition | ( | double | posX, |
double | posY, | ||
double | posZ, | ||
double | viewX, | ||
double | viewY, | ||
double | viewZ, | ||
int | viewport = 0 |
||
) |
Set the camera location and viewup according to the given arguments.
[in] | posX | the x co-ordinate of the camera location |
[in] | posY | the y co-ordinate of the camera location |
[in] | posZ | the z co-ordinate of the camera location |
[in] | viewX | the x component of the view up direction of the camera |
[in] | viewY | the y component of the view up direction of the camera |
[in] | viewZ | the z component of the view up direction of the camera |
[in] | viewport | the viewport to modify camera of, if 0, modifies all cameras |
Definition at line 1313 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::setFullScreen | ( | bool | mode | ) | [inline] |
Enables/Disabled the underlying window mode to full screen.
[in] | mode | true for full screen, false otherwise |
Definition at line 120 of file pcl_visualizer.h.
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)
[in] | property | the property type |
[in] | val1 | the first value to be set |
[in] | val2 | the second value to be set |
[in] | val3 | the third value to be set |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud's rendering properties should be modified (default: all) |
Definition at line 918 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.
[in] | property | the property type |
[in] | value | the value to be set |
[in] | id | the point cloud object id (default: cloud) |
[in] | viewport | the view port where the Point Cloud's rendering properties should be modified (default: all) |
Definition at line 993 of file pcl_visualizer.cpp.
Changes the visual representation for all actors to points representation.
Definition at line 2369 of file pcl_visualizer.cpp.
Changes the visual representation for all actors to surface representation.
Definition at line 2350 of file pcl_visualizer.cpp.
Changes the visual representation for all actors to wireframe representation.
Definition at line 2388 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.
[in] | property | the property type |
[in] | value | the value to be set |
[in] | id | the shape object id |
[in] | viewport | the view port where the shape's properties should be modified (default: all) |
Definition at line 1093 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)
[in] | property | the property type |
[in] | val1 | the first value to be set |
[in] | val2 | the second value to be set |
[in] | val3 | the third value to be set |
[in] | id | the shape object id |
[in] | viewport | the view port where the shape's properties should be modified (default: all) |
Definition at line 1049 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.
[in,out] | iren | the vtkRenderWindowInteractor object to set up |
[in,out] | win | a vtkRenderWindow object that the interactor is attached to |
Definition at line 208 of file pcl_visualizer.cpp.
void pcl::visualization::PCLVisualizer::setWindowBorders | ( | bool | mode | ) | [inline] |
Enables or disable the underlying window borders.
[in] | mode | true for borders, false otherwise |
Definition at line 132 of file pcl_visualizer.h.
Spin method. Calls the interactor and runs an internal loop.
Definition at line 291 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.
[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 301 of file pcl_visualizer.cpp.
Update camera parameters and render.
Definition at line 1187 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.
[out] | cells | the vtkIdTypeArray object (set of cells) to update |
[out] | initcells | a 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_points | the number of points in the new cloud. This dictates how many cells we need to generate |
Definition at line 2977 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::updateColorHandlerIndex | ( | const std::string & | id, |
int | index | ||
) |
Update/set the color index of a renderered PointCloud based on its ID.
[in] | id | the point cloud object id |
[in] | index | the color handler index to use |
Definition at line 2132 of file pcl_visualizer.cpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 988 of file pcl_visualizer.hpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | geometry_handler | the geometry handler to use |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 1019 of file pcl_visualizer.hpp.
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.
[in] | cloud | the input point cloud dataset |
[in] | color_handler | the color handler to use |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 1053 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 750 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 762 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.
[in] | cloud | the input point cloud dataset |
[in] | id | the point cloud object id to update (default: cloud) |
Definition at line 775 of file pcl_visualizer.h.
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.
[in] | cloud | the polygonal mesh point cloud |
[in] | vertices | the polygonal mesh vertices |
[in] | id | the polygon object id (default: "polygon") |
Definition at line 1264 of file pcl_visualizer.hpp.
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.
[in] | id | the shape or cloud object id (i.e., given on addLine etc.) |
[in] | pose | the new pose |
Definition at line 1203 of file pcl_visualizer.cpp.
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.
[in] | center | the center of the sphere |
[in] | radius | the radius of the sphere |
[in] | r | the red channel of the color that the sphere should be rendered with |
[in] | g | the green channel of the color that the sphere should be rendered with |
[in] | b | the blue channel of the color that the sphere should be rendered with |
[in] | id | the sphere id/name (default: "sphere") |
Definition at line 525 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.
[in] | text | the text to update |
[in] | xpos | the new X position on screen |
[in] | ypos | the new Y position on screen |
[in] | id | the text object id (default: equal to the "text" parameter) |
Definition at line 2050 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.
[in] | text | the text to update |
[in] | xpos | the new X position on screen |
[in] | ypos | the new Y position on screen |
[in] | r | the red color value |
[in] | g | the green color value |
[in] | b | the blue color vlaue |
[in] | id | the text object id (default: equal to the "text" parameter) |
Definition at line 2075 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.
[in] | text | the text to update |
[in] | xpos | the new X position on screen |
[in] | ypos | the new Y position on screen |
[in] | fontsize | the fontsize of the text |
[in] | r | the red color value |
[in] | g | the green color value |
[in] | b | the blue color vlaue |
[in] | id | the text object id (default: equal to the "text" parameter) |
Definition at line 2102 of file pcl_visualizer.cpp.
bool pcl::visualization::PCLVisualizer::wasStopped | ( | ) | const [inline] |
Returns true when the user tried to close the window.
Definition at line 960 of file pcl_visualizer.h.
Camera view, window position and size.
Definition at line 1388 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::camera_set_ [private] |
Boolean that holds whether or not the camera parameters were manually initialized.
Definition at line 1574 of file pcl_visualizer.h.
Internal list with actor pointers and name IDs for point clouds.
Definition at line 1565 of file pcl_visualizer.h.
Internal list with actor pointers and viewpoint for coordinates.
Definition at line 1571 of file pcl_visualizer.h.
vtkSmartPointer<ExitCallback> pcl::visualization::PCLVisualizer::exit_callback_ [private] |
Definition at line 1553 of file pcl_visualizer.h.
vtkSmartPointer<ExitMainLoopTimerCallback> pcl::visualization::PCLVisualizer::exit_main_loop_timer_callback_ [private] |
Callback object enabling us to leave the main loop, when a timer fires.
Definition at line 1552 of file pcl_visualizer.h.
vtkSmartPointer<vtkRenderWindowInteractor> pcl::visualization::PCLVisualizer::interactor_ [protected] |
The render window interactor.
Definition at line 1494 of file pcl_visualizer.h.
vtkSmartPointer<vtkRendererCollection> pcl::visualization::PCLVisualizer::rens_ [private] |
The collection of renderers used.
Definition at line 1556 of file pcl_visualizer.h.
Internal list with actor pointers and name IDs for shapes.
Definition at line 1568 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::stopped_ [private] |
Set to false if the interaction loop is running.
Definition at line 1546 of file pcl_visualizer.h.
vtkSmartPointer<PCLVisualizerInteractorStyle> pcl::visualization::PCLVisualizer::style_ [private] |
The render window interactor style.
Definition at line 1562 of file pcl_visualizer.h.
int pcl::visualization::PCLVisualizer::timer_id_ [private] |
Global timer ID. Used in destructor only.
Definition at line 1549 of file pcl_visualizer.h.
vtkSmartPointer<vtkRenderWindow> pcl::visualization::PCLVisualizer::win_ [private] |
The render window.
Definition at line 1559 of file pcl_visualizer.h.