Point Cloud Library (PCL)
1.3.1
|
PCL Visualizer main class. More...
#include <pcl/visualization/pcl_visualizer.h>
Classes | |
struct | ExitCallback |
struct | ExitMainLoopTimerCallback |
Public Types | |
typedef PointCloudGeometryHandler < sensor_msgs::PointCloud2 > | GeometryHandler |
typedef GeometryHandler::Ptr | GeometryHandlerPtr |
typedef GeometryHandler::ConstPtr | GeometryHandlerConstPtr |
typedef PointCloudColorHandler < sensor_msgs::PointCloud2 > | ColorHandler |
typedef ColorHandler::Ptr | ColorHandlerPtr |
typedef ColorHandler::ConstPtr | ColorHandlerConstPtr |
Public Member Functions | |
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. | |
virtual | ~PCLVisualizer () |
PCL Visualizer destructor. | |
boost::signals2::connection | registerKeyboardCallback (boost::function< void(const pcl::visualization::KeyboardEvent &)>) |
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 &)>) |
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 &)>) |
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. | |
void | spin () |
Spin method. | |
void | spinOnce (int time=1, bool force_redraw=false) |
Spin once method. | |
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::Matrix4f &t, int viewport=0) |
Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw. | |
bool | removeCoordinateSystem (int viewport=0) |
Removes a previously added 3D axes (coordinate system) | |
bool | removePointCloud (const std::string &id="cloud", int viewport=0) |
Removes a Point Cloud from screen, based on a given ID. | |
bool | removeShape (const std::string &id="cloud", int viewport=0) |
Removes an added shape from screen (line, polygon, etc.), based on a given ID. | |
bool | removeText3D (const std::string &id="cloud", int viewport=0) |
Removes an added 3D text from the scene, based on a given ID. | |
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. | |
void | setBackgroundColor (const double &r, const double &g, const double &b, int viewport=0) |
Set the viewport's background color. | |
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. | |
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 | 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 | 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. | |
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) |
Updates the XYZRGB data for an existing cloud object id on 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. | |
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 | 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 | 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 | 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. | |
void | removeCorrespondences (const std::string &id="correspondences", int viewport=0) |
Remove the specified correspondences from the display. | |
int | getColorHandlerIndex (const std::string &id) |
Get the color handler index of a rendered PointCloud based on its ID. | |
int | getGeometryHandlerIndex (const std::string &id) |
Get the geometry handler index of a rendered PointCloud based on its ID. | |
bool | updateColorHandlerIndex (const std::string &id, int index) |
Update/set the color index of a renderered PointCloud based on its ID. | |
bool | setPointCloudRenderingProperties (int property, double val1, double val2, double val3, const std::string &id="cloud", int viewport=0) |
Set the rendering properties of a PointCloud (3x values - e.g., RGB) | |
bool | setPointCloudRenderingProperties (int property, double value, const std::string &id="cloud", int viewport=0) |
Set the rendering properties of a PointCloud. | |
bool | getPointCloudRenderingProperties (int property, double &value, const std::string &id="cloud") |
Get the rendering properties of a PointCloud. | |
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) | |
bool | wasStopped () const |
Returns true when the user tried to close the window. | |
void | resetStoppedFlag () |
Set the stopped flag back to false. | |
void | createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport) |
Create a new viewport from [xmin,ymin] -> [xmax,ymax]. | |
template<typename PointT > | |
bool | addPolygon (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, double r, double g, double b, const std::string &id="polygon", int viewport=0) |
Add a polygon (polyline) that represents the input point cloud (connects all points in order) | |
template<typename PointT > | |
bool | addPolygon (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &id="polygon", int viewport=0) |
Add a polygon (polyline) that represents the input point cloud (connects all points in order) | |
template<typename 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. | |
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 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 | 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 | 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 | addCylinder (const pcl::ModelCoefficients &coefficients, const std::string &id="cylinder", int viewport=0) |
Add a cylinder from a set of given model coefficients. | |
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 | addLine (const pcl::ModelCoefficients &coefficients, const std::string &id="line", int viewport=0) |
Add a line from a set of given model coefficients. | |
bool | addPlane (const pcl::ModelCoefficients &coefficients, const std::string &id="plane", int viewport=0) |
Add a plane from a set of given model coefficients. | |
bool | 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. | |
bool | addCube (const pcl::ModelCoefficients &coefficients, const std::string &id="cube", int viewport=0) |
Add a cube from a set of given model coefficients. | |
void | setRepresentationToSurfaceForAllActors () |
Changes the visual representation for all actors to surface representation. | |
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. | |
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. | |
void | initCameraParameters () |
Initialize camera parameters with some default values. | |
bool | getCameraParameters (int argc, char **argv) |
Search for camera parameters at the command line and set them internally. | |
bool | cameraParamsSet () const |
Checks whether the camera parameters were manually loaded from file. | |
void | updateCamera () |
Update camera parameters and render. | |
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 | setCameraPosition (double posX, double posY, double posZ, double viewX, double viewY, double viewZ) |
Set the camera location and viewup according to the given arguments. | |
void | getCameras (std::vector< Camera > &cameras) |
Get the current camera parameters. | |
Eigen::Affine3f | getViewerPose () |
Get the current viewing pose. | |
void | saveScreenshot (const std::string &file) |
Save the current rendered image to disk, as a PNG screenshot. | |
vtkSmartPointer< vtkRenderWindow > | getRenderWindow () |
Return a pointer to the underlying VTK Render Window used. | |
void | createInteractor () |
Create the internal Interactor object. | |
Public Attributes | |
Camera | camera_ |
Camera view, window position and size. |
PCL Visualizer main class.
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 |
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 |
virtual pcl::visualization::PCLVisualizer::~PCLVisualizer | ( | ) | [virtual] |
PCL Visualizer destructor.
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.
pt1 | the first (start) point on the line |
pt2 | the second (end) point on the line |
r | the red channel of the color that the line should be rendered with |
g | the green channel of the color that the line should be rendered with |
b | the blue channel of the color that the line should be rendered with |
id | the line id/name (default: "arrow") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 360 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.
coefficients | the model coefficients (x, y, radius) |
id | the circle id/name (default: "circle") |
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);
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.
coefficients | the model coefficients (point_on_axis, axis_direction, radiu) |
id | the cone id/name (default: "cone") |
viewport | (optional) the id of the new viewport (default: 0) |
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.
scale | the scale of the axes (default: 1) |
viewport | the view port where the 3D axes should be added (default: all) |
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.
scale | the scale of the axes (default: 1) |
x | the X position of the axes |
y | the Y position of the axes |
z | the Z position of the axes |
viewport | the view port where the 3D axes should be added (default: all) |
void pcl::visualization::PCLVisualizer::addCoordinateSystem | ( | double | scale, |
const Eigen::Matrix4f & | t, | ||
int | viewport = 0 |
||
) |
Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw.
scale | the scale of the axes (default: 1) |
t | transformation matrix |
tube_size | the size of tube(radius of each orthogonal axies ,default: 1) |
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
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] | line_ids | A vector of strings into which the IDs of the newly drawn lines will be added |
[in] | id | the polygon object id (default: "correspondences") |
[in] | viewport | the view port where the correspondences should be added (default: all) |
Definition at line 626 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] | line_ids | A vector of strings into which the IDs of the newly drawn lines will be added |
[in] | id | the polygon object id (default: "correspondences") |
[in] | viewport | the view port where the correspondences should be added (default: all) |
Definition at line 685 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.
coefficients | the model coefficients (Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth) |
id | the cone id/name (default: "cube") |
viewport | (optional) the id of the new viewport (default: 0) |
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.
coefficients | the model coefficients (point_on_axis, axis_direction, radius) |
id | the cylinder id/name (default: "cylinder") |
viewport | (optional) the id of the new viewport (default: 0) |
// 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);
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.
pt1 | the first (start) point on the line |
pt2 | the second (end) point on the line |
id | the line id/name (default: "line") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 389 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.
pt1 | the first (start) point on the line |
pt2 | the second (end) point on the line |
r | the red channel of the color that the line should be rendered with |
g | the green channel of the color that the line should be rendered with |
b | the blue channel of the color that the line should be rendered with |
id | the line id/name (default: "line") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 333 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.
coefficients | the model coefficients (point_on_line, direction) |
id | the line id/name (default: "line") |
viewport | (optional) the id of the new viewport (default: 0) |
// 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);
bool pcl::visualization::PCLVisualizer::addModelFromPLYFile | ( | const std::string & | filename, |
const std::string & | id = "PLYModel" , |
||
int | viewport = 0 |
||
) |
Add a PLYmodel as a mesh.
filename | of the ply file |
id | the model id/name (default: "PLYModel") |
viewport | (optional) the id of the new viewport (default: 0) |
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.
filename | of the ply file |
transform | transformation to apply |
id | the model id/name (default: "PLYModel") |
viewport | (optional) the id of the new viewport (default: 0) |
bool pcl::visualization::PCLVisualizer::addModelFromPolyData | ( | vtkSmartPointer< vtkPolyData > | polydata, |
const std::string & | id = "PolyData" , |
||
int | viewport = 0 |
||
) |
Add a vtkPolydata as a mesh.
polydata | vtkPolyData |
id | the model id/name (default: "PolyData") |
viewport | (optional) the id of the new viewport (default: 0) |
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.
polydata | vtkPolyData |
transform | transformation to apply |
id | the model id/name (default: "PolyData") |
viewport | (optional) the id of the new viewport (default: 0) |
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.
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) |
// 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);
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.
cloud | the input point cloud dataset |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 50 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 |
||
) |
Updates the XYZRGB data for an existing cloud object id on screen.
cloud | the input point cloud dataset |
color_handler | the RGB color handler to use |
id | the point cloud object id to update (default: cloud) |
cloud | the input point cloud dataset |
geometry_handler | use a geometry handler object to extract the XYZ data |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 61 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).
cloud | the input point cloud dataset |
geometry_handler | use a geometry handler object to extract the XYZ data |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 82 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.
cloud | the input point cloud dataset |
color_handler | a specific PointCloud visualizer handler for colors |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 105 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).
cloud | the input point cloud dataset |
color_handler | a specific PointCloud visualizer handler for colors |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 130 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).
cloud | the input point cloud dataset |
geometry_handler | a specific PointCloud visualizer handler for geometry |
color_handler | a specific PointCloud visualizer handler for colors |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 151 of file pcl_visualizer.hpp.
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.
cloud | the input point cloud dataset |
color_handler | a specific PointCloud visualizer handler for colors |
geometry_handler | use a geometry handler object to extract the XYZ data |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 172 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.
cloud | the input point cloud dataset |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 562 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.
cloud | the input point cloud dataset |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 575 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.
cloud | the input point cloud dataset containing XYZ data and normals |
level | display only every level'th point (default: 100) |
scale | the normal arrow scale (default: 0.02m) |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 542 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.
cloud | the input point cloud dataset containing the XYZ data |
normals | the input point cloud dataset containing the normal data |
level | display only every level'th point (default: 100) |
scale | the normal arrow scale (default: 0.02m) |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
Definition at line 551 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.
cloud | the input point cloud dataset containing the XYZ data |
normals | the input point cloud dataset containing the normal data |
pcs | the input point cloud dataset containing the principal curvatures data |
level | display only every level'th point (default: 100) |
scale | the normal arrow scale (default: 1.0)) |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud should be added (default: all) |
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)
cloud | the point cloud dataset representing the polygon |
r | the red channel of the color that the polygon should be rendered with |
g | the green channel of the color that the polygon should be rendered with |
b | the blue channel of the color that the polygon should be rendered with |
id | (optional) the polygon id/name (default: "polygon") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 294 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)
cloud | the point cloud dataset representing the polygon |
id | the polygon id/name (default: "polygon") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 323 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.
polymesh | the polygonal mesh |
id | the polygon object id (default: "polygon") |
viewport | the view port where the PolygonMesh should be added (default: all) |
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.
cloud | the polygonal mesh point cloud |
vertices | the polygonal mesh vertices |
id | the polygon object id (default: "polygon") |
viewport | the view port where the PolygonMesh should be added (default: all) |
Definition at line 1006 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) |
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.
center | the center of the sphere |
radius | the radius of the sphere |
id | the line id/name (default: "sphere") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 469 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.
center | the center of the sphere |
radius | the radius of the sphere |
r | the red channel of the color that the sphere should be rendered with |
g | the green channel of the color that the sphere should be rendered with |
b | the blue channel of the color that the sphere should be rendered with |
id | the line id/name (default: "sphere") |
viewport | (optional) the id of the new viewport (default: 0) |
Definition at line 441 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.
coefficients | the model coefficients (sphere center, radius) |
id | the sphere id/name (default: "sphere") |
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);
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.
text | the text to add |
xpos | the X position on screen where the text should be added |
ypos | the Y position on screen where the text should be added |
id | the text object id (default: equal to the "text" parameter) |
viewport | the view port (default: all) |
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.
text | the text to add |
xpos | the X position on screen where the text should be added |
ypos | the Y position on screen where the text should be added |
r | the red color value |
g | the green color value |
b | the blue color vlaue |
id | the text object id (default: equal to the "text" parameter) |
viewport | the view port (default: all) |
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.
text | the text to add |
xpos | the X position on screen where the text should be added |
ypos | the Y position on screen where the text should be added |
fontsize | the fontsize of the text |
r | the red color value |
g | the green color value |
b | the blue color vlaue |
id | the text object id (default: equal to the "text" parameter) |
viewport | the view port (default: all) |
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.
text | the text to add |
position | the world position where the text should be added |
textScale | the scale of the text to render |
r | the red color value |
g | the green color value |
b | the blue color value |
id | the text object id (default: equal to the "text" parameter) |
viewport | the view port (default: all) |
Definition at line 476 of file pcl_visualizer.hpp.
bool pcl::visualization::PCLVisualizer::cameraParamsSet | ( | ) | const |
Checks whether the camera parameters were manually loaded from file.
void pcl::visualization::PCLVisualizer::createInteractor | ( | ) |
Create the internal Interactor object.
void pcl::visualization::PCLVisualizer::createViewPort | ( | double | xmin, |
double | ymin, | ||
double | xmax, | ||
double | ymax, | ||
int & | viewport | ||
) |
Create a new viewport from [xmin,ymin] -> [xmax,ymax].
xmin | the minimum X coordinate for the viewport (0.0 <= 1.0) |
ymin | the minimum Y coordinate for the viewport (0.0 <= 1.0) |
xmax | the maximum X coordinate for the viewport (0.0 <= 1.0) |
ymax | the maximum Y coordinate for the viewport (0.0 <= 1.0) |
viewport | the id of the new viewport |
bool pcl::visualization::PCLVisualizer::getCameraParameters | ( | int | argc, |
char ** | argv | ||
) |
Search for camera parameters at the command line and set them internally.
argc | |
argv |
void pcl::visualization::PCLVisualizer::getCameras | ( | std::vector< Camera > & | cameras | ) |
Get the current camera parameters.
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 683 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.
id | the point cloud object id |
Definition at line 696 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.
property | the property type |
value | the resultant property value |
id | the point cloud object id (default: cloud) |
vtkSmartPointer<vtkRenderWindow> pcl::visualization::PCLVisualizer::getRenderWindow | ( | ) | [inline] |
Return a pointer to the underlying VTK Render Window used.
Definition at line 1173 of file pcl_visualizer.h.
Eigen::Affine3f pcl::visualization::PCLVisualizer::getViewerPose | ( | ) |
Get the current viewing pose.
void pcl::visualization::PCLVisualizer::initCameraParameters | ( | ) |
Initialize camera parameters with some default values.
boost::signals2::connection pcl::visualization::PCLVisualizer::registerKeyboardCallback | ( | boost::function< void(const pcl::visualization::KeyboardEvent &)> | ) |
Register a callback boost::function for keyboard events.
[in] | a | boost function that will be registered as a callback for a keyboard event |
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 127 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 139 of file pcl_visualizer.h.
boost::signals2::connection pcl::visualization::PCLVisualizer::registerMouseCallback | ( | boost::function< void(const pcl::visualization::MouseEvent &)> | ) |
Register a callback function for mouse events.
[in] | a | boost function that will be registered as a callback for a mouse event |
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 157 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 169 of file pcl_visualizer.h.
boost::signals2::connection pcl::visualization::PCLVisualizer::registerPointPickingCallback | ( | boost::function< void(const pcl::visualization::PointPickingEvent &)> | ) |
Register a callback function for point picking events.
[in] | a | boost function that will be registered as a callback for a point picking event |
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 187 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 199 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::removeAllPointClouds | ( | int | viewport = 0 | ) |
Remove all point cloud data on screen from the given viewport.
viewport | view port from where the clouds should be removed (default: all) |
bool pcl::visualization::PCLVisualizer::removeAllShapes | ( | int | viewport = 0 | ) |
Remove all 3D shape data on screen from the given viewport.
viewport | view port from where the shapes should be removed (default: all) |
bool pcl::visualization::PCLVisualizer::removeCoordinateSystem | ( | int | viewport = 0 | ) |
Removes a previously added 3D axes (coordinate system)
viewport | view port where the 3D axes should be removed from (default: all) |
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 674 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.
id | the point cloud object id (i.e., given on addPointCloud) |
viewport | view port from where the Point Cloud should be removed (default: all) |
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.
id | the shape object id (i.e., given on addLine etc.) |
viewport | view port from where the Point Cloud should be removed (default: all) |
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.
id | the 3D text id (i.e., given on addText3D etc.) |
viewport | view port from where the 3D text should be removed (default: all) |
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.
xres | and yres are the size of the window used to render the scene |
cloud | is the rendered point cloud |
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
xres | and yres are the size of the window used to render the partial view of the object |
cloud | is a vector of pointcloud with XYZ information that represent the model as seen from the respective viewpoints. |
poses | represent the transformation from object coordinates to camera coordinates for the respective viewpoint. |
enthropies | are values between 0 and 1 representing which percentage of the model is seen from the respective viewpoint. |
tesselation_level | represents the number of subdivisions applied to the triangles of original icosahedron. |
view_angle | field of view of the virtual camera |
use_vertices | if true, use the vertices of tesselated icosahedron (12,42,...) or if false, use the faces of tesselated icosahedron (20,80,...) |
void pcl::visualization::PCLVisualizer::resetCamera | ( | ) |
Reset camera parameters and render.
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.
id | the point cloud object id (default: cloud) |
void pcl::visualization::PCLVisualizer::resetStoppedFlag | ( | ) | [inline] |
Set the stopped flag back to false.
Definition at line 780 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 |
void pcl::visualization::PCLVisualizer::setBackgroundColor | ( | const double & | r, |
const double & | g, | ||
const double & | b, | ||
int | viewport = 0 |
||
) |
void pcl::visualization::PCLVisualizer::setCameraPosition | ( | double | posX, |
double | posY, | ||
double | posZ, | ||
double | viewX, | ||
double | viewY, | ||
double | viewZ | ||
) |
Set the camera location and viewup according to the given arguments.
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 normal direction of the camera |
viewY | the y component of the normal direction of the camera |
viewZ | the z component of the normal direction of the camera |
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)
property | the property type |
val1 | the first value to be set |
val2 | the second value to be set |
val3 | the third value to be set |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud's rendering properties should be modified (default: all) |
bool pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties | ( | int | property, |
double | value, | ||
const std::string & | id = "cloud" , |
||
int | viewport = 0 |
||
) |
Set the rendering properties of a PointCloud.
property | the property type |
value | the value to be set |
id | the point cloud object id (default: cloud) |
viewport | the view port where the Point Cloud's rendering properties should be modified (default: all) |
void pcl::visualization::PCLVisualizer::setRepresentationToSurfaceForAllActors | ( | ) |
Changes the visual representation for all actors to surface representation.
bool pcl::visualization::PCLVisualizer::setShapeRenderingProperties | ( | int | property, |
double | value, | ||
const std::string & | id, | ||
int | viewport = 0 |
||
) |
Set the rendering properties of a shape.
property | the property type |
value | the value to be set |
id | the shape object id |
viewport | the view port where the shape's properties should be modified (default: all) |
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)
property | the property type |
val1 | the first value to be set |
val2 | the second value to be set |
val3 | the third value to be set |
id | the shape object id |
viewport | the view port where the shape's properties should be modified (default: all) |
void pcl::visualization::PCLVisualizer::spin | ( | ) |
Spin method.
Calls the interactor and runs an internal loop.
void pcl::visualization::PCLVisualizer::spinOnce | ( | int | time = 1 , |
bool | force_redraw = false |
||
) |
Spin once method.
Calls the interactor and updates the screen once.
time | - How long (in ms) should the visualization loop be allowed to run. |
force_redraw | - if false it might return without doing anything if the interactor's framerate does not require a redraw yet. |
void pcl::visualization::PCLVisualizer::updateCamera | ( | ) |
Update camera parameters and render.
bool pcl::visualization::PCLVisualizer::updateColorHandlerIndex | ( | const std::string & | id, |
int | index | ||
) |
Update/set the color index of a renderered PointCloud based on its ID.
id | the point cloud object id |
index | the color handler index to use |
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.
cloud | the input point cloud dataset |
id | the point cloud object id to update (default: cloud) |
Definition at line 881 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.
geometry_handler | the geometry handler to use |
id | the point cloud object id to update (default: cloud) |
Definition at line 908 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.
cloud | the input point cloud dataset |
color_handler | the color handler to use |
id | the point cloud object id to update (default: cloud) |
Definition at line 938 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.
cloud | the input point cloud dataset |
id | the point cloud object id to update (default: cloud) |
Definition at line 588 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.
cloud | the input point cloud dataset |
id | the point cloud object id to update (default: cloud) |
Definition at line 600 of file pcl_visualizer.h.
bool pcl::visualization::PCLVisualizer::wasStopped | ( | ) | const [inline] |
Returns true when the user tried to close the window.
Definition at line 776 of file pcl_visualizer.h.
Camera view, window position and size.
Definition at line 1114 of file pcl_visualizer.h.