42 #include <pcl/correspondence.h>
43 #include <pcl/ModelCoefficients.h>
44 #include <pcl/PolygonMesh.h>
45 #include <pcl/TextureMesh.h>
47 #include <pcl/console/print.h>
48 #include <pcl/visualization/common/actor_map.h>
49 #include <pcl/visualization/common/common.h>
50 #include <pcl/visualization/point_cloud_geometry_handlers.h>
51 #include <pcl/visualization/point_cloud_color_handlers.h>
52 #include <pcl/visualization/point_picking_event.h>
53 #include <pcl/visualization/area_picking_event.h>
54 #include <pcl/visualization/interactor_style.h>
59 class vtkRenderWindow;
60 class vtkOrientationMarkerWidget;
61 class vtkAppendPolyData;
62 class vtkRenderWindow;
63 class vtkRenderWindowInteractor;
65 class vtkInteractorStyle;
70 class vtkUnstructuredGrid;
75 template <
typename T>
class PlanarPolygon;
77 namespace visualization
89 using Ptr = shared_ptr<PCLVisualizer>;
90 using ConstPtr = shared_ptr<const PCLVisualizer>;
104 PCLVisualizer (
const std::string &name =
"",
const bool create_interactor =
true);
134 const bool create_interactor =
true);
166 boost::signals2::connection
174 inline boost::signals2::connection
186 template<
typename T>
inline boost::signals2::connection
196 boost::signals2::connection
204 inline boost::signals2::connection
216 template<
typename T>
inline boost::signals2::connection
226 boost::signals2::connection
234 boost::signals2::connection
243 template<
typename T>
inline boost::signals2::connection
253 boost::signals2::connection
261 boost::signals2::connection
270 template<
typename T>
inline boost::signals2::connection
286 spinOnce (
int time = 1,
bool force_redraw =
false);
315 addCoordinateSystem (
double scale,
float x,
float y,
float z,
const std::string &
id =
"reference",
int viewport = 0);
353 addCoordinateSystem (
double scale,
const Eigen::Affine3f& t,
const std::string &
id =
"reference",
int viewport = 0);
379 return (removePointCloud (
id, viewport));
434 const std::string &
id =
"",
int viewport = 0);
447 addText (
const std::string &text,
int xpos,
int ypos,
double r,
double g,
double b,
448 const std::string &
id =
"",
int viewport = 0);
462 addText (
const std::string &text,
int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
463 const std::string &
id =
"",
int viewport = 0);
475 const std::string &
id =
"");
488 int xpos,
int ypos,
double r,
double g,
double b,
489 const std::string &
id =
"");
503 int xpos,
int ypos,
int fontsize,
double r,
double g,
double b,
504 const std::string &
id =
"");
552 template <
typename Po
intT>
bool
553 addText3D (
const std::string &text,
555 double textScale = 1.0,
556 double r = 1.0,
double g = 1.0,
double b = 1.0,
557 const std::string &
id =
"",
int viewport = 0);
573 template <
typename Po
intT>
bool
574 addText3D (
const std::string &text,
576 double orientation[3],
577 double textScale = 1.0,
578 double r = 1.0,
double g = 1.0,
double b = 1.0,
579 const std::string &
id =
"",
int viewport = 0);
588 return (cloud_actor_map_->find (
id) != cloud_actor_map_->end () ||
589 shape_actor_map_->find (
id) != shape_actor_map_->end () ||
590 coordinate_actor_map_->find (
id) != coordinate_actor_map_-> end());
600 template <
typename Po
intNT>
bool
602 int level = 100,
float scale = 0.02f,
603 const std::string &
id =
"cloud",
int viewport = 0);
613 template <
typename Po
intT,
typename Po
intNT>
bool
616 int level = 100,
float scale = 0.02f,
617 const std::string &
id =
"cloud",
int viewport = 0);
627 template <
typename Po
intNT>
bool
631 int level = 100,
float scale = 1.0f,
632 const std::string &
id =
"cloud",
int viewport = 0);
643 template <
typename Po
intT,
typename Po
intNT>
bool
644 addPointCloudPrincipalCurvatures (
648 int level = 100,
float scale = 1.0f,
649 const std::string &
id =
"cloud",
int viewport = 0);
659 template <
typename Po
intT,
typename GradientT>
bool
662 int level = 100,
double scale = 1e-6,
663 const std::string &
id =
"cloud",
int viewport = 0);
670 template <
typename Po
intT>
bool
672 const std::string &
id =
"cloud",
int viewport = 0);
679 template <
typename Po
intT>
bool
681 const std::string &
id =
"cloud");
689 template <
typename Po
intT>
bool
692 const std::string &
id =
"cloud");
700 template <
typename Po
intT>
bool
703 const std::string &
id =
"cloud");
711 template <
typename Po
intT>
bool
714 const std::string &
id =
"cloud",
int viewport = 0);
728 template <
typename Po
intT>
bool
731 const std::string &
id =
"cloud",
int viewport = 0);
739 template <
typename Po
intT>
bool
742 const std::string &
id =
"cloud",
int viewport = 0);
756 template <
typename Po
intT>
bool
759 const std::string &
id =
"cloud",
int viewport = 0);
774 template <
typename Po
intT>
bool
778 const std::string &
id =
"cloud",
int viewport = 0);
799 const Eigen::Vector4f& sensor_origin,
800 const Eigen::Quaternion<float>& sensor_orientation,
801 const std::string &
id =
"cloud",
int viewport = 0);
820 const Eigen::Vector4f& sensor_origin,
821 const Eigen::Quaternion<float>& sensor_orientation,
822 const std::string &
id =
"cloud",
int viewport = 0);
841 const Eigen::Vector4f& sensor_origin,
842 const Eigen::Quaternion<float>& sensor_orientation,
843 const std::string &
id =
"cloud",
int viewport = 0);
852 template <
typename Po
intT>
bool
856 const std::string &
id =
"cloud",
int viewport = 0);
865 const std::string &
id =
"cloud",
int viewport = 0)
867 return (addPointCloud<pcl::PointXYZ> (cloud,
id, viewport));
878 const std::string &
id =
"cloud",
int viewport = 0)
881 return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id, viewport));
891 const std::string &
id =
"cloud",
int viewport = 0)
894 return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id, viewport));
904 const std::string &
id =
"cloud",
int viewport = 0)
907 return (addPointCloud<pcl::PointXYZL> (cloud, color_handler,
id, viewport));
917 const std::string &
id =
"cloud")
919 return (updatePointCloud<pcl::PointXYZ> (cloud,
id));
929 const std::string &
id =
"cloud")
932 return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler,
id));
942 const std::string &
id =
"cloud")
945 return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler,
id));
955 const std::string &
id =
"cloud")
958 return (updatePointCloud<pcl::PointXYZL> (cloud, color_handler,
id));
968 const std::string &
id =
"polygon",
977 template <
typename Po
intT>
bool
979 const std::vector<pcl::Vertices> &vertices,
980 const std::string &
id =
"polygon",
989 template <
typename Po
intT>
bool
991 const std::vector<pcl::Vertices> &vertices,
992 const std::string &
id =
"polygon");
1001 const std::string &
id =
"polygon");
1010 const std::string &
id =
"polyline",
1020 template <
typename Po
intT>
bool
1023 const std::vector<int> & correspondences,
1024 const std::string &
id =
"correspondences",
1034 const std::string &
id =
"texture",
1046 template <
typename Po
intT>
bool
1051 const std::string &
id =
"correspondences",
1053 bool overwrite =
false);
1062 template <
typename Po
intT>
bool
1066 const std::string &
id =
"correspondences",
1070 return (addCorrespondences<PointT> (source_points, target_points,
1071 correspondences, 1,
id, viewport));
1082 template <
typename Po
intT>
bool
1083 updateCorrespondences (
1088 const std::string &
id =
"correspondences",
1098 template <
typename Po
intT>
bool
1103 const std::string &
id =
"correspondences",
1107 return (updateCorrespondences<PointT> (source_points, target_points,
1108 correspondences, 1,
id, viewport));
1148 const std::string &
id =
"cloud",
int viewport = 0);
1160 const std::string &
id =
"cloud",
int viewport = 0);
1171 const std::string &
id =
"cloud",
int viewport = 0);
1181 const std::string &
id =
"cloud");
1194 const std::string &
id =
"cloud");
1213 const std::string &
id,
int viewport = 0);
1225 const std::string &
id,
int viewport = 0);
1238 const std::string &
id,
int viewport = 0);
1281 template <
typename Po
intT>
bool
1283 double r,
double g,
double b,
1284 const std::string &
id =
"polygon",
int viewport = 0);
1292 template <
typename Po
intT>
bool
1294 const std::string &
id =
"polygon",
1305 template <
typename Po
intT>
bool
1307 double r,
double g,
double b,
1308 const std::string &
id =
"polygon",
1317 template <
typename P1,
typename P2>
bool
1318 addLine (
const P1 &pt1,
const P2 &pt2,
const std::string &
id =
"line",
1330 template <
typename P1,
typename P2>
bool
1331 addLine (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1332 const std::string &
id =
"line",
int viewport = 0);
1346 template <
typename P1,
typename P2>
bool
1347 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
1348 const std::string &
id =
"arrow",
int viewport = 0);
1363 template <
typename P1,
typename P2>
bool
1364 addArrow (
const P1 &pt1,
const P2 &pt2,
double r,
double g,
double b,
bool display_length,
1365 const std::string &
id =
"arrow",
int viewport = 0);
1382 template <
typename P1,
typename P2>
bool
1383 addArrow (
const P1 &pt1,
const P2 &pt2,
1384 double r_line,
double g_line,
double b_line,
1385 double r_text,
double g_text,
double b_text,
1386 const std::string &
id =
"arrow",
int viewport = 0);
1395 template <
typename Po
intT>
bool
1396 addSphere (
const PointT ¢er,
double radius,
const std::string &
id =
"sphere",
1408 template <
typename Po
intT>
bool
1409 addSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1410 const std::string &
id =
"sphere",
int viewport = 0);
1420 template <
typename Po
intT>
bool
1421 updateSphere (
const PointT ¢er,
double radius,
double r,
double g,
double b,
1422 const std::string &
id =
"sphere");
1431 const std::string &
id =
"PolyData",
1443 const std::string &
id =
"PolyData",
1453 const std::string &
id =
"PLYModel",
1465 const std::string &
id =
"PLYModel",
1496 const std::string &
id =
"cylinder",
1523 const std::string &
id =
"sphere",
1551 const std::string &
id =
"line",
1579 const char *
id =
"line",
1582 return addLine (coefficients, std::string (
id), viewport);
1607 const std::string &
id =
"plane",
1612 const std::string &
id =
"plane",
1635 const std::string &
id =
"circle",
1645 const std::string &
id =
"cone",
1655 const std::string &
id =
"cube",
1668 addCube (
const Eigen::Vector3f &translation,
const Eigen::Quaternionf &rotation,
1669 double width,
double height,
double depth,
1670 const std::string &
id =
"cube",
1687 addCube (
float x_min,
float x_max,
float y_min,
float y_max,
float z_min,
float z_max,
1688 double r = 1.0,
double g = 1.0,
double b = 1.0,
const std::string &
id =
"cube",
int viewport = 0);
1744 std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies,
int tesselation_level,
1745 float view_angle = 45,
float radius_sphere = 1,
bool use_vertices =
true);
1817 double view_x,
double view_y,
double view_z,
1818 double up_x,
double up_y,
double up_z,
int viewport = 0);
1831 double up_x,
double up_y,
double up_z,
int viewport = 0);
1907 return (cloud_actor_map_);
1914 return (shape_actor_map_);
1956 vtkRenderWindow *win);
1966 vtkRenderWindow *win,
1967 vtkInteractorStyle *style);
1992 void setupRenderWindow (
const std::string& name);
2000 void setDefaultWindowSizeAndPos ();
2008 void setupCamera (
int argc,
char **argv);
2010 struct PCL_EXPORTS ExitMainLoopTimerCallback :
public vtkCommand
2012 static ExitMainLoopTimerCallback* New ()
2014 return (
new ExitMainLoopTimerCallback);
2017 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2023 struct PCL_EXPORTS ExitCallback :
public vtkCommand
2025 static ExitCallback* New ()
2027 return (
new ExitCallback);
2030 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2032 PCLVisualizer* pcl_visualizer;
2036 struct PCL_EXPORTS FPSCallback :
public vtkCommand
2038 static FPSCallback *New () {
return (
new FPSCallback); }
2040 FPSCallback () : actor (), pcl_visualizer (), decimated (), last_fps(0.0f) {}
2041 FPSCallback (
const FPSCallback& src) : vtkCommand (src), actor (src.actor), pcl_visualizer (src.pcl_visualizer), decimated (src.decimated), last_fps (src.last_fps) {}
2042 FPSCallback& operator = (
const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps;
return (*
this); }
2045 Execute (vtkObject*,
unsigned long event_id,
void*)
override;
2047 vtkTextActor *actor;
2048 PCLVisualizer* pcl_visualizer;
2091 bool camera_file_loaded_;
2139 bool use_scalars =
true)
const;
2149 bool use_scalars =
true)
const;
2157 template <
typename Po
intT>
void
2168 template <
typename Po
intT>
void
2169 convertPointCloudToVTKPolyData (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2180 convertPointCloudToVTKPolyData (
const GeometryHandlerConstPtr &geometry_handler,
2195 vtkIdType nr_points);
2207 template <
typename Po
intT>
bool
2208 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2209 const PointCloudColorHandler<PointT> &color_handler,
2210 const std::string &
id,
2212 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2213 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2225 template <
typename Po
intT>
bool
2226 fromHandlersToScreen (
const PointCloudGeometryHandler<PointT> &geometry_handler,
2227 const ColorHandlerConstPtr &color_handler,
2228 const std::string &
id,
2230 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2231 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2244 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2245 const ColorHandlerConstPtr &color_handler,
2246 const std::string &
id,
2248 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2249 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2261 template <
typename Po
intT>
bool
2262 fromHandlersToScreen (
const GeometryHandlerConstPtr &geometry_handler,
2263 const PointCloudColorHandler<PointT> &color_handler,
2264 const std::string &
id,
2266 const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2267 const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2293 getTransformationMatrix (
const Eigen::Vector4f &origin,
2294 const Eigen::Quaternion<float> &orientation,
2295 Eigen::Matrix4f &transformation);
2306 vtkTexture* vtk_tex)
const;
2313 getUniqueCameraFile (
int argc,
char **argv);
2332 const Eigen::Quaternion<float> &orientation,
2341 Eigen::Matrix4f &m);
2347 #include <pcl/visualization/impl/pcl_visualizer.hpp>
PlanarPolygon represents a planar (2D) polygon, potentially in a 3D space.
PointCloud represents the base class in PCL for storing collections of 3D points.
std::vector< PointCloud< PointT >, Eigen::aligned_allocator< PointCloud< PointT > > > CloudVectorType
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
/brief Class representing 3D area picking events.
Camera class holds a set of camera parameters together with the window pos/size.
/brief Class representing key hit/release events
PCL Visualizer main class.
void close()
Stop the interaction and close the visualizaton window.
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 addPolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polygon", int viewport=0)
Add a PolygonMesh object to screen.
void createViewPort(double xmin, double ymin, double xmax, double ymax, int &viewport)
Create a new viewport from [xmin,ymin] -> [xmax,ymax].
void renderViewTesselatedSphere(int xres, int yres, pcl::PointCloud< pcl::PointXYZ >::CloudVectorType &cloud, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &poses, std::vector< float > &enthropies, int tesselation_level, float view_angle=45, float radius_sphere=1, bool use_vertices=true)
The purpose of this method is to render a CAD model added to the visualizer from different viewpoints...
shared_ptr< PCLVisualizer > Ptr
void setPosition(int x, int y)
Set the position in screen coordinates.
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const GeometryHandlerConstPtr &geometry_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
Add a binary blob Point Cloud to screen.
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const 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 removePointCloud(const std::string &id="cloud", int viewport=0)
Removes a Point Cloud from screen, based on a given ID.
bool updateCoordinateSystemPose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing coordinate system.
boost::signals2::connection registerAreaPickingCallback(std::function< void(const pcl::visualization::AreaPickingEvent &)> cb)
Register a callback function for area picking events.
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZRGBA Point Cloud to screen.
static void convertToVtkMatrix(const Eigen::Matrix4f &m, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
Convert Eigen::Matrix4f to vtkMatrix4x4.
bool addTextureMesh(const pcl::TextureMesh &polymesh, const std::string &id="texture", int viewport=0)
Add a TextureMesh object to screen.
boost::signals2::connection registerMouseCallback(void(T::*callback)(const pcl::visualization::MouseEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for mouse events.
GeometryHandler::Ptr GeometryHandlerPtr
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 setShapeRenderingProperties(int property, double val1, double val2, const std::string &id, int viewport=0)
Set the rendering properties of a shape (2x values - e.g., LUT minmax values)
void setCameraPosition(double pos_x, double pos_y, double pos_z, double view_x, double view_y, double view_z, double up_x, double up_y, double up_z, int viewport=0)
Set the camera pose given by position, viewpoint and up vector.
vtkSmartPointer< vtkRenderWindowInteractor > interactor_
The render window interactor.
boost::signals2::connection registerPointPickingCallback(std::function< void(const pcl::visualization::PointPickingEvent &)> cb)
Register a callback function for point picking events.
CloudActorMapPtr getCloudActorMap()
Return a pointer to the CloudActorMap this visualizer uses.
void setupInteractor(vtkRenderWindowInteractor *iren, vtkRenderWindow *win, vtkInteractorStyle *style)
Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object attach...
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 removeCoordinateSystem(const std::string &id="reference", int viewport=0)
Removes a previously added 3D axes (coordinate system)
vtkSmartPointer< vtkRendererCollection > getRendererCollection()
Return a pointer to the underlying VTK Renderer Collection.
bool updatePolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polygon")
Update a PolygonMesh object on screen.
void saveCameraParameters(const std::string &file)
Save the camera parameters to disk, as a .cam file.
void addCoordinateSystem(double scale, const Eigen::Affine3f &t, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw.
bool updateColorHandlerIndex(const std::string &id, int index)
Update/set the color index of a rendered PointCloud based on its ID.
void setBackgroundColor(const double &r, const double &g, const double &b, int viewport=0)
Set the viewport's background color.
void updateCamera()
Update camera parameters and render.
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.
virtual ~PCLVisualizer()
PCL Visualizer destructor.
bool updateShapePose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing shape.
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 removeAllCoordinateSystems(int viewport=0)
Removes all existing 3D axes (coordinate systems)
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZL >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZL Point Cloud to screen.
void addCoordinateSystem(double scale=1.0, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at 0,0,0.
boost::signals2::connection registerKeyboardCallback(void(T::*callback)(const pcl::visualization::KeyboardEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for keyboard events.
bool updatePointCloudPose(const std::string &id, const Eigen::Affine3f &pose)
Set the pose of an existing point cloud.
bool setPointCloudSelected(const bool selected, const std::string &id="cloud")
Set whether the point cloud is selected or not.
bool cameraParamsSet() const
Checks whether the camera parameters were manually loaded.
bool updateText(const std::string &text, int xpos, int ypos, const std::string &id="")
Update a text to screen.
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.
bool addModelFromPolyData(vtkSmartPointer< vtkPolyData > polydata, const std::string &id="PolyData", int viewport=0)
Add a vtkPolydata as a mesh.
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 addText(const std::string &text, int xpos, int ypos, const std::string &id="", int viewport=0)
Add a text to screen.
boost::signals2::connection registerAreaPickingCallback(void(T::*callback)(const pcl::visualization::AreaPickingEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for area picking events.
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 addCircle(const pcl::ModelCoefficients &coefficients, const std::string &id="circle", int viewport=0)
Add a circle from a set of given model coefficients.
PCLVisualizer(vtkSmartPointer< vtkRenderer > ren, vtkSmartPointer< vtkRenderWindow > wind, const std::string &name="", const bool create_interactor=true)
PCL Visualizer constructor.
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 cameraFileLoaded() const
Checks whether a camera file were automatically loaded.
void createViewPortCamera(const int viewport)
Create a new separate camera for the given viewport.
void getCameras(std::vector< Camera > &cameras)
Get the current camera parameters.
std::string getCameraFile() const
Get camera file for camera parameter saving/restoring.
bool addCube(float x_min, float x_max, float y_min, float y_max, float z_min, float z_max, double r=1.0, double g=1.0, double b=1.0, const std::string &id="cube", int viewport=0)
Add a cube.
bool 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.
ShapeActorMapPtr getShapeActorMap()
Return a pointer to the ShapeActorMap this visualizer uses.
GeometryHandler::ConstPtr GeometryHandlerConstPtr
void setFullScreen(bool mode)
Enables/Disabled the underlying window mode to full screen.
static void convertToVtkMatrix(const Eigen::Vector4f &origin, const Eigen::Quaternion< float > &orientation, vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix)
Convert origin and orientation to vtkMatrix4x4.
bool wasStopped() const
Returns true when the user tried to close the window.
void setLookUpTableID(const std::string id)
Set the ID of a cloud or shape to be used for LUT display.
bool addPlane(const pcl::ModelCoefficients &coefficients, double x, double y, double z, const std::string &id="plane", int viewport=0)
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.
void setCameraFieldOfView(double fovy, int viewport=0)
Set the camera vertical field of view.
void removeOrientationMarkerWidgetAxes()
Disables the Orientatation Marker Widget so it is removed from the renderer.
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.
bool addCone(const pcl::ModelCoefficients &coefficients, const std::string &id="cone", int viewport=0)
Add a cone from a set of given model coefficients.
int getGeometryHandlerIndex(const std::string &id)
Get the geometry handler index of a rendered PointCloud based on its ID.
void spinOnce(int time=1, bool force_redraw=false)
Spin once method.
PCLVisualizer(const std::string &name="", const bool create_interactor=true)
PCL Visualizer constructor.
void setSize(int xw, int yw)
Set the window size in screen coordinates.
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 removeAllPointClouds(int viewport=0)
Remove all point cloud data on screen from the given viewport.
ColorHandler::ConstPtr ColorHandlerConstPtr
bool addPointCloud(const pcl::PCLPointCloud2::ConstPtr &cloud, const ColorHandlerConstPtr &color_handler, const Eigen::Vector4f &sensor_origin, const Eigen::Quaternion< float > &sensor_orientation, const std::string &id="cloud", int viewport=0)
Add a binary blob Point Cloud to screen.
bool addModelFromPLYFile(const std::string &filename, const std::string &id="PLYModel", int viewport=0)
Add a PLYmodel as a mesh.
void setCameraParameters(const Camera &camera, int viewport=0)
Set the camera parameters by given a full camera data structure.
boost::signals2::connection registerPointPickingCallback(void(T::*callback)(const pcl::visualization::PointPickingEvent &, void *), T &instance, void *cookie=nullptr)
Register a callback function for point picking events.
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.
void setUseVbos(bool use_vbos)
Use Vertex Buffer Objects renderers.
bool loadCameraParameters(const std::string &file)
Load camera parameters from a camera parameters file.
void setShowFPS(bool show_fps)
Sets whether the 2D overlay text showing the framerate of the window is displayed or not.
bool getCameraParameters(int argc, char **argv)
Search for camera parameters at the command line and set them internally.
int getColorHandlerIndex(const std::string &id)
Get the color handler index of a rendered PointCloud based on its ID.
void setupInteractor(vtkRenderWindowInteractor *iren, vtkRenderWindow *win)
Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object attached to a giv...
void setCameraClipDistances(double near, double far, int viewport=0)
Set the camera clipping distances.
void createInteractor()
Create the internal Interactor object.
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 removeAllShapes(int viewport=0)
Remove all 3D shape data on screen from the given viewport.
float getFPS() const
Get the current rendering framerate.
bool addPointCloudPrincipalCurvatures(const typename pcl::PointCloud< PointNT >::ConstPtr &cloud, const typename pcl::PointCloud< pcl::PrincipalCurvatures >::ConstPtr &pcs, int level=100, float scale=1.0f, const std::string &id="cloud", int viewport=0)
Add the estimated principal curvatures of a Point Cloud to screen.
boost::signals2::connection registerKeyboardCallback(void(*callback)(const pcl::visualization::KeyboardEvent &, void *), void *cookie=nullptr)
Register a callback function for keyboard events.
ColorHandler::Ptr ColorHandlerPtr
bool setShapeRenderingProperties(int property, double value, const std::string &id, int viewport=0)
Set the rendering properties of a shape.
void initCameraParameters()
Initialize camera parameters with some default values.
vtkSmartPointer< vtkRenderWindow > getRenderWindow()
Return a pointer to the underlying VTK Render Window used.
PCLVisualizer(int &argc, char **argv, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New(), const bool create_interactor=true)
PCL Visualizer constructor.
void setCameraPosition(double pos_x, double pos_y, double pos_z, double up_x, double up_y, double up_z, int viewport=0)
Set the camera location and viewup according to the given arguments.
void resetCamera()
Reset camera parameters and render.
boost::signals2::connection registerMouseCallback(void(*callback)(const pcl::visualization::MouseEvent &, void *), void *cookie=nullptr)
Register a callback function for mouse events.
void addCoordinateSystem(double scale, float x, float y, float z, const std::string &id="reference", int viewport=0)
Adds 3D axes describing a coordinate system to screen at x, y, z.
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 removePolygonMesh(const std::string &id="polygon", int viewport=0)
Removes a PolygonMesh from screen, based on a given ID.
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 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 contains(const std::string &id) const
Check if the cloud, shape, or coordinate with the given id was already added to this visualizer.
void setWindowName(const std::string &name)
Set the visualizer window name.
void setWindowBorders(bool mode)
Enables or disable the underlying window borders.
boost::signals2::connection registerPointPickingCallback(void(*callback)(const pcl::visualization::PointPickingEvent &, void *), void *cookie=nullptr)
Register a callback function for point picking events.
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZL >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZL data for an existing cloud object id on screen.
bool removeText3D(const std::string &id="cloud", int viewport=0)
Removes an added 3D text from the scene, based on a given ID.
boost::signals2::connection registerAreaPickingCallback(void(*callback)(const pcl::visualization::AreaPickingEvent &, void *), void *cookie=nullptr)
Register a callback function for area picking events.
bool setPointCloudRenderingProperties(int property, double value, const std::string &id="cloud", int viewport=0)
Set the rendering properties of a PointCloud.
bool getPointCloudRenderingProperties(RenderingProperties property, double &val1, double &val2, double &val3, const std::string &id="cloud")
Get the rendering properties of a PointCloud.
void saveScreenshot(const std::string &file)
Save the current rendered image to disk, as a PNG screenshot.
PCLVisualizer(int &argc, char **argv, vtkSmartPointer< vtkRenderer > ren, vtkSmartPointer< vtkRenderWindow > wind, const std::string &name="", PCLVisualizerInteractorStyle *style=PCLVisualizerInteractorStyle::New(), const bool create_interactor=true)
PCL Visualizer constructor.
static void convertToEigenMatrix(const vtkSmartPointer< vtkMatrix4x4 > &vtk_matrix, Eigen::Matrix4f &m)
Convert vtkMatrix4x4 to an Eigen4f.
bool addPolylineFromPolygonMesh(const pcl::PolygonMesh &polymesh, const std::string &id="polyline", int viewport=0)
Add a Polygonline from a polygonMesh object to screen.
bool getPointCloudRenderingProperties(int property, double &value, const std::string &id="cloud")
Get the rendering properties of a PointCloud.
bool updatePointCloud(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &cloud, const std::string &id="cloud")
Updates the XYZRGBA data for an existing cloud object id on screen.
bool removeShape(const std::string &id="cloud", int viewport=0)
Removes an added shape from screen (line, polygon, etc.), based on a given ID.
boost::signals2::connection registerMouseCallback(std::function< void(const pcl::visualization::MouseEvent &)> cb)
Register a callback function for mouse events.
void resetStoppedFlag()
Set the stopped flag back to false.
shared_ptr< const PCLVisualizer > ConstPtr
void getCameraParameters(Camera &camera, int viewport=0) const
Get camera parameters of a given viewport (0 means default viewport).
boost::signals2::connection registerKeyboardCallback(std::function< void(const pcl::visualization::KeyboardEvent &)> cb)
Register a callback std::function for keyboard events.
Eigen::Affine3f getViewerPose(int viewport=0)
Get the current viewing pose.
bool addPointCloud(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud, const std::string &id="cloud", int viewport=0)
Add a PointXYZ Point Cloud to screen.
void addOrientationMarkerWidgetAxes(vtkRenderWindowInteractor *interactor)
Adds a widget which shows an interactive axes display for orientation.
bool addCylinder(const pcl::ModelCoefficients &coefficients, const std::string &id="cylinder", int viewport=0)
Add a cylinder from a set of given model coefficients.
void setRepresentationToPointsForAllActors()
Changes the visual representation for all actors to points representation.
bool setPointCloudRenderingProperties(int property, double val1, double val2, const std::string &id="cloud", int viewport=0)
Set the rendering properties of a PointCloud (2x values - e.g., LUT minmax values)
bool addLine(const pcl::ModelCoefficients &coefficients, const char *id="line", int viewport=0)
Add a line from a set of given model coefficients.
bool updateCorrespondences(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)
Update the specified correspondences to the display.
void removeCorrespondences(const std::string &id="correspondences", int viewport=0)
Remove the specified correspondences from the display.
bool addModelFromPolyData(vtkSmartPointer< vtkPolyData > polydata, vtkSmartPointer< vtkTransform > transform, const std::string &id="PolyData", int viewport=0)
Add a vtkPolydata as a mesh.
void setCameraParameters(const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport=0)
Set the camera parameters via an intrinsics and and extrinsics matrix.
vtkSmartPointer< PCLVisualizerInteractorStyle > getInteractorStyle()
Get a pointer to the current interactor style used.
bool addSphere(const pcl::ModelCoefficients &coefficients, const std::string &id="sphere", int viewport=0)
Add a sphere from a set of given model coefficients.
PCLVisualizerInteractorStyle defines an unique, custom VTK based interactory style for PCL Visualizer...
static PCLVisualizerInteractorStyle * New()
Base Handler class for PointCloud colors.
shared_ptr< const PointCloudColorHandler< PointCloud > > ConstPtr
shared_ptr< PointCloudColorHandler< PointCloud > > Ptr
Base Handler class for PointCloud colors.
Label field handler class for colors.
RGBA handler class for colors.
RGB handler class for colors.
Base handler class for PointCloud geometry.
shared_ptr< PointCloudGeometryHandler< PointCloud > > Ptr
shared_ptr< const PointCloudGeometryHandler< PointCloud > > ConstPtr
Base handler class for PointCloud geometry.
/brief Class representing 3D point picking events.
RenderingProperties
Set of rendering properties.
shared_ptr< CloudActorMap > CloudActorMapPtr
shared_ptr< ShapeActorMap > ShapeActorMapPtr
shared_ptr< CoordinateActorMap > CoordinateActorMapPtr
PCL_EXPORTS void allocVtkUnstructuredGrid(vtkSmartPointer< vtkUnstructuredGrid > &polydata)
Allocate a new unstructured grid smartpointer.
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.