Point Cloud Library (PCL)  1.14.1-dev
pcl_visualizer.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  */
38 
39 #pragma once
40 
41 // PCL includes
42 #include <pcl/correspondence.h>
43 #include <pcl/ModelCoefficients.h>
44 #include <pcl/PolygonMesh.h>
45 #include <pcl/TextureMesh.h>
46 //
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>
55 
56 #include <vtkOrientationMarkerWidget.h>
57 #include <vtkRenderWindowInteractor.h>
58 
59 // VTK includes
60 class vtkPolyData;
61 class vtkTextActor;
62 class vtkRenderWindow;
63 class vtkAppendPolyData;
64 class vtkRenderWindow;
65 class vtkTransform;
66 class vtkInteractorStyle;
67 class vtkLODActor;
68 class vtkProp;
69 class vtkActor;
70 class vtkDataSet;
71 class vtkUnstructuredGrid;
72 class vtkCellArray;
73 
74 namespace pcl
75 {
76  template <typename T> class PointCloud;
77  template <typename T> class PlanarPolygon;
78 
79  namespace visualization
80  {
81  namespace details
82  {
83  PCL_EXPORTS vtkIdType fillCells(std::vector<int>& lookup, const std::vector<pcl::Vertices>& vertices, vtkSmartPointer<vtkCellArray> cell_array, int max_size_of_polygon);
84  }
85 
86  /** \brief PCL Visualizer main class.
87  * \author Radu B. Rusu
88  * \ingroup visualization
89  * \note This class can NOT be used across multiple threads. Only call functions of objects of this class
90  * from the same thread that they were created in! Some methods, e.g. addPointCloud, will crash if called
91  * from other threads.
92  */
94  {
95  public:
96  using Ptr = shared_ptr<PCLVisualizer>;
97  using ConstPtr = shared_ptr<const PCLVisualizer>;
98 
102 
106 
107  /** \brief PCL Visualizer constructor.
108  * \param[in] name the window name (empty by default)
109  * \param[in] create_interactor if true (default), create an interactor, false otherwise
110  */
111  PCLVisualizer (const std::string &name = "", const bool create_interactor = true);
112 
113  /** \brief PCL Visualizer constructor. It looks through the passed argv arguments to find the "-cam *.cam" argument.
114  * If the search failed, the name for cam file is calculated with boost uuid. If there is no such file, camera is not initialized.
115  * \param[in] argc
116  * \param[in] argv
117  * \param[in] name the window name (empty by default)
118  * \param[in] style interactor style (defaults to PCLVisualizerInteractorStyle)
119  * \param[in] create_interactor if true (default), create an interactor, false otherwise
120  */
121  PCLVisualizer (int &argc, char **argv, const std::string &name = "",
122  PCLVisualizerInteractorStyle* style = PCLVisualizerInteractorStyle::New (), const bool create_interactor = true);
123 
124  /** \brief PCL Visualizer constructor.
125  * \param[in] ren custom vtk renderer
126  * \param[in] wind custom vtk render window
127  * \param[in] create_interactor if true (default), create an interactor, false otherwise
128  */
129  PCLVisualizer (vtkSmartPointer<vtkRenderer> ren, vtkSmartPointer<vtkRenderWindow> wind, const std::string &name = "", const bool create_interactor = true);
130 
131  /** \brief PCL Visualizer constructor.
132  * \param[in] argc
133  * \param[in] argv
134  * \param[in] ren custom vtk renderer
135  * \param[in] wind custom vtk render window
136  * \param[in] style interactor style (defaults to PCLVisualizerInteractorStyle)
137  * \param[in] create_interactor if true (default), create an interactor, false otherwise
138  */
139  PCLVisualizer (int &argc, char **argv, vtkSmartPointer<vtkRenderer> ren, vtkSmartPointer<vtkRenderWindow> wind, const std::string &name = "",
141  const bool create_interactor = true);
142 
143 
144  /** \brief PCL Visualizer destructor. */
145  virtual ~PCLVisualizer ();
146 
147  /** \brief Enables/Disabled the underlying window mode to full screen.
148  * \note This might or might not work, depending on your window manager.
149  * See the VTK documentation for additional details.
150  * \param[in] mode true for full screen, false otherwise
151  */
152  void
153  setFullScreen (bool mode);
154 
155  /** \brief Set the visualizer window name.
156  * \param[in] name the name of the window
157  */
158  void
159  setWindowName (const std::string &name);
160 
161  /** \brief Enables or disable the underlying window borders.
162  * \note This might or might not work, depending on your window manager.
163  * See the VTK documentation for additional details.
164  * \param[in] mode true for borders, false otherwise
165  */
166  void
167  setWindowBorders (bool mode);
168 
169  /** \brief Register a callback std::function for keyboard events
170  * \param[in] cb a std function that will be registered as a callback for a keyboard event
171  * \return a connection object that allows to disconnect the callback function.
172  */
173  boost::signals2::connection
175 
176  /** \brief Register a callback function for keyboard events
177  * \param[in] callback the function that will be registered as a callback for a keyboard event
178  * \param[in] cookie user data that is passed to the callback
179  * \return a connection object that allows to disconnect the callback function.
180  */
181  inline boost::signals2::connection
182  registerKeyboardCallback (void (*callback) (const pcl::visualization::KeyboardEvent&, void*), void* cookie = nullptr)
183  {
184  return (registerKeyboardCallback ([=] (const pcl::visualization::KeyboardEvent& e) { (*callback) (e, cookie); }));
185  }
186 
187  /** \brief Register a callback function for keyboard events
188  * \param[in] callback the member function that will be registered as a callback for a keyboard event
189  * \param[in] instance instance to the class that implements the callback function
190  * \param[in] cookie user data that is passed to the callback
191  * \return a connection object that allows to disconnect the callback function.
192  */
193  template<typename T> inline boost::signals2::connection
194  registerKeyboardCallback (void (T::*callback) (const pcl::visualization::KeyboardEvent&, void*), T& instance, void* cookie = nullptr)
195  {
196  return (registerKeyboardCallback ([=, &instance] (const pcl::visualization::KeyboardEvent& e) { (instance.*callback) (e, cookie); }));
197  }
198 
199  /** \brief Register a callback function for mouse events
200  * \param[in] cb a std function that will be registered as a callback for a mouse event
201  * \return a connection object that allows to disconnect the callback function.
202  */
203  boost::signals2::connection
204  registerMouseCallback (std::function<void (const pcl::visualization::MouseEvent&)> cb);
205 
206  /** \brief Register a callback function for mouse events
207  * \param[in] callback the function that will be registered as a callback for a mouse event
208  * \param[in] cookie user data that is passed to the callback
209  * \return a connection object that allows to disconnect the callback function.
210  */
211  inline boost::signals2::connection
212  registerMouseCallback (void (*callback) (const pcl::visualization::MouseEvent&, void*), void* cookie = nullptr)
213  {
214  return (registerMouseCallback ([=] (const pcl::visualization::MouseEvent& e) { (*callback) (e, cookie); }));
215  }
216 
217  /** \brief Register a callback function for mouse events
218  * \param[in] callback the member function that will be registered as a callback for a mouse event
219  * \param[in] instance instance to the class that implements the callback function
220  * \param[in] cookie user data that is passed to the callback
221  * \return a connection object that allows to disconnect the callback function.
222  */
223  template<typename T> inline boost::signals2::connection
224  registerMouseCallback (void (T::*callback) (const pcl::visualization::MouseEvent&, void*), T& instance, void* cookie = nullptr)
225  {
226  return (registerMouseCallback ([=, &instance] (const pcl::visualization::MouseEvent& e) { (instance.*callback) (e, cookie); }));
227  }
228 
229  /** \brief Register a callback function for point picking events
230  * \param[in] cb a std function that will be registered as a callback for a point picking event
231  * \return a connection object that allows to disconnect the callback function.
232  */
233  boost::signals2::connection
235 
236  /** \brief Register a callback function for point picking events
237  * \param[in] callback the function that will be registered as a callback for a point picking event
238  * \param[in] cookie user data that is passed to the callback
239  * \return a connection object that allows to disconnect the callback function.
240  */
241  boost::signals2::connection
242  registerPointPickingCallback (void (*callback) (const pcl::visualization::PointPickingEvent&, void*), void* cookie = nullptr);
243 
244  /** \brief Register a callback function for point picking events
245  * \param[in] callback the member function that will be registered as a callback for a point picking event
246  * \param[in] instance instance to the class that implements the callback function
247  * \param[in] cookie user data that is passed to the callback
248  * \return a connection object that allows to disconnect the callback function.
249  */
250  template<typename T> inline boost::signals2::connection
251  registerPointPickingCallback (void (T::*callback) (const pcl::visualization::PointPickingEvent&, void*), T& instance, void* cookie = nullptr)
252  {
253  return (registerPointPickingCallback ([=, &instance] (const pcl::visualization::PointPickingEvent& e) { (instance.*callback) (e, cookie); }));
254  }
255 
256  /** \brief Register a callback function for area picking events
257  * \param[in] cb a std function that will be registered as a callback for an area picking event
258  * \return a connection object that allows to disconnect the callback function.
259  */
260  boost::signals2::connection
262 
263  /** \brief Register a callback function for area picking events
264  * \param[in] callback the function that will be registered as a callback for an area picking event
265  * \param[in] cookie user data that is passed to the callback
266  * \return a connection object that allows to disconnect the callback function.
267  */
268  boost::signals2::connection
269  registerAreaPickingCallback (void (*callback) (const pcl::visualization::AreaPickingEvent&, void*), void* cookie = nullptr);
270 
271  /** \brief Register a callback function for area picking events
272  * \param[in] callback the member function that will be registered as a callback for an area picking event
273  * \param[in] instance instance to the class that implements the callback function
274  * \param[in] cookie user data that is passed to the callback
275  * \return a connection object that allows to disconnect the callback function.
276  */
277  template<typename T> inline boost::signals2::connection
278  registerAreaPickingCallback (void (T::*callback) (const pcl::visualization::AreaPickingEvent&, void*), T& instance, void* cookie = nullptr)
279  {
280  return (registerAreaPickingCallback ([=, &instance] (const pcl::visualization::AreaPickingEvent& e) { (instance.*callback) (e, cookie); }));
281  }
282 
283  /** \brief Spin method. Calls the interactor and runs an internal loop. */
284  void
285  spin ();
286 
287  /** \brief Spin once method. Calls the interactor and updates the screen once.
288  * \param[in] time - How long (in ms) should the visualization loop be allowed to run.
289  * \param[in] force_redraw - if false it might return without doing anything if the
290  * interactor's framerate does not require a redraw yet.
291  * \note This function may not return immediately after the specified time has elapsed, for example if
292  * the user continues to interact with the visualizer, meaning that there are still events to process.
293  */
294  void
295  spinOnce (int time = 1, bool force_redraw = false);
296 
297  /** \brief Adds a widget which shows an interactive axes display for orientation
298  * \param[in] interactor - Pointer to the vtk interactor object used by the PCLVisualizer window
299  */
300  void
301  addOrientationMarkerWidgetAxes (vtkRenderWindowInteractor* interactor);
302 
303  /** \brief Disables the Orientatation Marker Widget so it is removed from the renderer */
304  void
306 
307  /** \brief Adds 3D axes describing a coordinate system to screen at 0,0,0.
308  * \param[in] scale the scale of the axes (default: 1)
309  * \param[in] id the coordinate system object id (default: reference)
310  * \param[in] viewport the view port where the 3D axes should be added (default: all)
311  */
312  void
313  addCoordinateSystem (double scale = 1.0, const std::string& id = "reference", int viewport = 0);
314 
315  /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z
316  * \param[in] scale the scale of the axes (default: 1)
317  * \param[in] x the X position of the axes
318  * \param[in] y the Y position of the axes
319  * \param[in] z the Z position of the axes
320  * \param[in] id the coordinate system object id (default: reference)
321  * \param[in] viewport the view port where the 3D axes should be added (default: all)
322  */
323  void
324  addCoordinateSystem (double scale, float x, float y, float z, const std::string &id = "reference", int viewport = 0);
325 
326  /** \brief Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw
327  *
328  * \param[in] scale the scale of the axes (default: 1)
329  * \param[in] t transformation matrix
330  * \param[in] id the coordinate system object id (default: reference)
331  * \param[in] viewport the view port where the 3D axes should be added (default: all)
332  *
333  * RPY Angles
334  * Rotate the reference frame by the angle roll about axis x
335  * Rotate the reference frame by the angle pitch about axis y
336  * Rotate the reference frame by the angle yaw about axis z
337  *
338  * Description:
339  * Sets the orientation of the Prop3D. Orientation is specified as
340  * X,Y and Z rotations in that order, but they are performed as
341  * RotateZ, RotateX, and finally RotateY.
342  *
343  * All axies use right hand rule. x=red axis, y=green axis, z=blue axis
344  * z direction is point into the screen.
345  * \code
346  * z
347  * \
348  * \
349  * \
350  * -----------> x
351  * |
352  * |
353  * |
354  * |
355  * |
356  * |
357  * y
358  * \endcode
359  */
360 
361  void
362  addCoordinateSystem (double scale, const Eigen::Affine3f& t, const std::string &id = "reference", int viewport = 0);
363 
364  /** \brief Removes a previously added 3D axes (coordinate system)
365  * \param[in] id the coordinate system object id (default: reference)
366  * \param[in] viewport view port where the 3D axes should be removed from (default: all)
367  */
368  bool
369  removeCoordinateSystem (const std::string &id = "reference", int viewport = 0);
370 
371  /** \brief Removes a Point Cloud from screen, based on a given ID.
372  * \param[in] id the point cloud object id (i.e., given on \a addPointCloud)
373  * \param[in] viewport view port from where the Point Cloud should be removed (default: all)
374  * \return true if the point cloud is successfully removed and false if the point cloud is
375  * not actually displayed
376  */
377  bool
378  removePointCloud (const std::string &id = "cloud", int viewport = 0);
379 
380  /** \brief Removes a PolygonMesh from screen, based on a given ID.
381  * \param[in] id the polygon object id (i.e., given on \a addPolygonMesh)
382  * \param[in] viewport view port from where the PolygonMesh should be removed (default: all)
383  */
384  inline bool
385  removePolygonMesh (const std::string &id = "polygon", int viewport = 0)
386  {
387  // Polygon Meshes are represented internally as point clouds with special cell array structures since 1.4
388  return (removePointCloud (id, viewport));
389  }
390 
391  /** \brief Removes an added shape from screen (line, polygon, etc.), based on a given ID
392  * \note This methods also removes PolygonMesh objects and PointClouds, if they match the ID
393  * \param[in] id the shape object id (i.e., given on \a addLine etc.)
394  * \param[in] viewport view port from where the Point Cloud should be removed (default: all)
395  */
396  bool
397  removeShape (const std::string &id = "cloud", int viewport = 0);
398 
399  /** \brief Removes an added 3D text from the scene, based on a given ID
400  * \param[in] id the 3D text id (i.e., given on \a addText3D etc.)
401  * \param[in] viewport view port from where the 3D text should be removed (default: all)
402  */
403  bool
404  removeText3D (const std::string &id = "cloud", int viewport = 0);
405 
406  /** \brief Remove all point cloud data on screen from the given viewport.
407  * \param[in] viewport view port from where the clouds should be removed (default: all)
408  */
409  bool
410  removeAllPointClouds (int viewport = 0);
411 
412  /** \brief Remove all 3D shape data on screen from the given viewport.
413  * \param[in] viewport view port from where the shapes should be removed (default: all)
414  */
415  bool
416  removeAllShapes (int viewport = 0);
417 
418  /** \brief Removes all existing 3D axes (coordinate systems)
419  * \param[in] viewport view port where the 3D axes should be removed from (default: all)
420  */
421  bool
422  removeAllCoordinateSystems (int viewport = 0);
423 
424  /** \brief Set the viewport's background color.
425  * \param[in] r the red component of the RGB color
426  * \param[in] g the green component of the RGB color
427  * \param[in] b the blue component of the RGB color
428  * \param[in] viewport the view port (default: all)
429  */
430  void
431  setBackgroundColor (const double &r, const double &g, const double &b, int viewport = 0);
432 
433  /** \brief Add a text to screen
434  * \param[in] text the text to add
435  * \param[in] xpos the X position on screen where the text should be added
436  * \param[in] ypos the Y position on screen where the text should be added
437  * \param[in] id the text object id (default: equal to the "text" parameter)
438  * \param[in] viewport the view port (default: all)
439  */
440  bool
441  addText (const std::string &text,
442  int xpos, int ypos,
443  const std::string &id = "", int viewport = 0);
444 
445  /** \brief Add a text to screen
446  * \param[in] text the text to add
447  * \param[in] xpos the X position on screen where the text should be added
448  * \param[in] ypos the Y position on screen where the text should be added
449  * \param[in] r the red color value
450  * \param[in] g the green color value
451  * \param[in] b the blue color value
452  * \param[in] id the text object id (default: equal to the "text" parameter)
453  * \param[in] viewport the view port (default: all)
454  */
455  bool
456  addText (const std::string &text, int xpos, int ypos, double r, double g, double b,
457  const std::string &id = "", int viewport = 0);
458 
459  /** \brief Add a text to screen
460  * \param[in] text the text to add
461  * \param[in] xpos the X position on screen where the text should be added
462  * \param[in] ypos the Y position on screen where the text should be added
463  * \param[in] fontsize the fontsize of the text
464  * \param[in] r the red color value
465  * \param[in] g the green color value
466  * \param[in] b the blue color value
467  * \param[in] id the text object id (default: equal to the "text" parameter)
468  * \param[in] viewport the view port (default: all)
469  */
470  bool
471  addText (const std::string &text, int xpos, int ypos, int fontsize, double r, double g, double b,
472  const std::string &id = "", int viewport = 0);
473 
474 
475  /** \brief Update a text to screen
476  * \param[in] text the text to update
477  * \param[in] xpos the new X position on screen
478  * \param[in] ypos the new Y position on screen
479  * \param[in] id the text object id (default: equal to the "text" parameter)
480  */
481  bool
482  updateText (const std::string &text,
483  int xpos, int ypos,
484  const std::string &id = "");
485 
486  /** \brief Update a text to screen
487  * \param[in] text the text to update
488  * \param[in] xpos the new X position on screen
489  * \param[in] ypos the new Y position on screen
490  * \param[in] r the red color value
491  * \param[in] g the green color value
492  * \param[in] b the blue color value
493  * \param[in] id the text object id (default: equal to the "text" parameter)
494  */
495  bool
496  updateText (const std::string &text,
497  int xpos, int ypos, double r, double g, double b,
498  const std::string &id = "");
499 
500  /** \brief Update a text to screen
501  * \param[in] text the text to update
502  * \param[in] xpos the new X position on screen
503  * \param[in] ypos the new Y position on screen
504  * \param[in] fontsize the fontsize of the text
505  * \param[in] r the red color value
506  * \param[in] g the green color value
507  * \param[in] b the blue color value
508  * \param[in] id the text object id (default: equal to the "text" parameter)
509  */
510  bool
511  updateText (const std::string &text,
512  int xpos, int ypos, int fontsize, double r, double g, double b,
513  const std::string &id = "");
514 
515  /** \brief Set the pose of an existing shape.
516  *
517  * Returns false if the shape doesn't exist, true if the pose was successfully
518  * updated.
519  *
520  * \param[in] id the shape or cloud object id (i.e., given on \a addLine etc.)
521  * \param[in] pose the new pose
522  * \return false if no shape or cloud with the specified ID was found
523  */
524  bool
525  updateShapePose (const std::string &id, const Eigen::Affine3f& pose);
526 
527  /** \brief Set the pose of an existing coordinate system.
528  *
529  * Returns false if the coordinate system doesn't exist, true if the pose was successfully
530  * updated.
531  *
532  * \param[in] id the point cloud object id (i.e., given on \a addCoordinateSystem etc.)
533  * \param[in] pose the new pose
534  * \return false if no coordinate system with the specified ID was found
535  */
536  bool
537  updateCoordinateSystemPose (const std::string &id, const Eigen::Affine3f& pose);
538 
539  /** \brief Set the pose of an existing point cloud.
540  *
541  * Returns false if the point cloud doesn't exist, true if the pose was successfully
542  * updated.
543  *
544  * \param[in] id the point cloud object id (i.e., given on \a addPointCloud etc.)
545  * \param[in] pose the new pose
546  * \return false if no point cloud with the specified ID was found
547  */
548  bool
549  updatePointCloudPose (const std::string &id, const Eigen::Affine3f& pose);
550 
551  /** \brief Add a 3d text to the scene
552  * \param[in] text the text to add
553  * \param[in] position the world position where the text should be added
554  * \param[in] textScale the scale of the text to render
555  * \param[in] r the red color value
556  * \param[in] g the green color value
557  * \param[in] b the blue color value
558  * \param[in] id the text object id (default: equal to the "text" parameter)
559  * \param[in] viewport the view port (default: all)
560  */
561  template <typename PointT> bool
562  addText3D (const std::string &text,
563  const PointT &position,
564  double textScale = 1.0,
565  double r = 1.0, double g = 1.0, double b = 1.0,
566  const std::string &id = "", int viewport = 0);
567 
568  /** \brief Add a 3d text to the scene
569  * \param[in] text the text to add
570  * \param[in] position the world position where the text should be added
571  * \param[in] orientation the angles of rotation of the text around X, Y and Z axis,
572  in this order. The way the rotations are effectively done is the
573  Z-X-Y intrinsic rotations:
574  https://en.wikipedia.org/wiki/Euler_angles#Definition_by_intrinsic_rotations
575  * \param[in] textScale the scale of the text to render
576  * \param[in] r the red color value
577  * \param[in] g the green color value
578  * \param[in] b the blue color value
579  * \param[in] id the text object id (default: equal to the "text" parameter)
580  * \param[in] viewport the view port (default: all)
581  */
582  template <typename PointT> bool
583  addText3D (const std::string &text,
584  const PointT &position,
585  double orientation[3],
586  double textScale = 1.0,
587  double r = 1.0, double g = 1.0, double b = 1.0,
588  const std::string &id = "", int viewport = 0);
589 
590  /** \brief Check if the cloud, shape, or coordinate with the given id was already added to this visualizer.
591  * \param[in] id the id of the cloud, shape, or coordinate to check
592  * \return true if a cloud, shape, or coordinate with the specified id was found
593  */
594  inline bool
595  contains(const std::string &id) const
596  {
597  return (cloud_actor_map_->find (id) != cloud_actor_map_->end () ||
598  shape_actor_map_->find (id) != shape_actor_map_->end () ||
599  coordinate_actor_map_->find (id) != coordinate_actor_map_-> end());
600  }
601 
602  /** \brief Add the estimated surface normals of a Point Cloud to screen.
603  * \param[in] cloud the input point cloud dataset containing XYZ data and normals
604  * \param[in] level display only every level'th point (default: 100)
605  * \param[in] scale the normal arrow scale (default: 0.02m)
606  * \param[in] id the point cloud object id (default: cloud)
607  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
608  */
609  template <typename PointNT> bool
610  addPointCloudNormals (const typename pcl::PointCloud<PointNT>::ConstPtr &cloud,
611  int level = 100, float scale = 0.02f,
612  const std::string &id = "cloud", int viewport = 0);
613 
614  /** \brief Add the estimated surface normals of a Point Cloud to screen.
615  * \param[in] cloud the input point cloud dataset containing the XYZ data
616  * \param[in] normals the input point cloud dataset containing the normal data
617  * \param[in] level display only every level'th point (default: 100)
618  * \param[in] scale the normal arrow scale (default: 0.02m)
619  * \param[in] id the point cloud object id (default: cloud)
620  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
621  */
622  template <typename PointT, typename PointNT> bool
623  addPointCloudNormals (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
624  const typename pcl::PointCloud<PointNT>::ConstPtr &normals,
625  int level = 100, float scale = 0.02f,
626  const std::string &id = "cloud", int viewport = 0);
627 
628  /** \brief Add the estimated principal curvatures of a Point Cloud to screen.
629  * \param[in] cloud the input point cloud dataset containing the XYZ data and normals
630  * \param[in] pcs the input point cloud dataset containing the principal curvatures data
631  * \param[in] level display only every level'th point. Default: 100
632  * \param[in] scale the normal arrow scale. Default: 1.0
633  * \param[in] id the point cloud object id. Default: "cloud"
634  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
635  */
636  template <typename PointNT> bool
638  const typename pcl::PointCloud<PointNT>::ConstPtr &cloud,
640  int level = 100, float scale = 1.0f,
641  const std::string &id = "cloud", int viewport = 0);
642 
643  /** \brief Add the estimated principal curvatures of a Point Cloud to screen.
644  * \param[in] cloud the input point cloud dataset containing the XYZ data
645  * \param[in] normals the input point cloud dataset containing the normal data
646  * \param[in] pcs the input point cloud dataset containing the principal curvatures data
647  * \param[in] level display only every level'th point. Default: 100
648  * \param[in] scale the normal arrow scale. Default: 1.0
649  * \param[in] id the point cloud object id. Default: "cloud"
650  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
651  */
652  template <typename PointT, typename PointNT> bool
653  addPointCloudPrincipalCurvatures (
654  const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
655  const typename pcl::PointCloud<PointNT>::ConstPtr &normals,
657  int level = 100, float scale = 1.0f,
658  const std::string &id = "cloud", int viewport = 0);
659 
660  /** \brief Add the estimated surface intensity gradients of a Point Cloud to screen.
661  * \param[in] cloud the input point cloud dataset containing the XYZ data
662  * \param[in] gradients the input point cloud dataset containing the intensity gradient data
663  * \param[in] level display only every level'th point (default: 100)
664  * \param[in] scale the intensity gradient arrow scale (default: 1e-6m)
665  * \param[in] id the point cloud object id (default: cloud)
666  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
667  */
668  template <typename PointT, typename GradientT> bool
669  addPointCloudIntensityGradients (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
670  const typename pcl::PointCloud<GradientT>::ConstPtr &gradients,
671  int level = 100, double scale = 1e-6,
672  const std::string &id = "cloud", int viewport = 0);
673 
674  /** \brief Add a Point Cloud (templated) to screen.
675  * \param[in] cloud the input point cloud dataset
676  * \param[in] id the point cloud object id (default: cloud)
677  * \param viewport the view port where the Point Cloud should be added (default: all)
678  */
679  template <typename PointT> bool
680  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
681  const std::string &id = "cloud", int viewport = 0);
682 
683  /** \brief Updates the XYZ data for an existing cloud object id on screen.
684  * \param[in] cloud the input point cloud dataset
685  * \param[in] id the point cloud object id to update (default: cloud)
686  * \return false if no cloud with the specified ID was found
687  */
688  template <typename PointT> bool
689  updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
690  const std::string &id = "cloud");
691 
692  /** \brief Updates the XYZ data for an existing cloud object id on screen.
693  * \param[in] cloud the input point cloud dataset
694  * \param[in] geometry_handler the geometry handler to use
695  * \param[in] id the point cloud object id to update (default: cloud)
696  * \return false if no cloud with the specified ID was found
697  */
698  template <typename PointT> bool
699  updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
700  const PointCloudGeometryHandler<PointT> &geometry_handler,
701  const std::string &id = "cloud");
702 
703  /** \brief Updates the XYZ data for an existing cloud object id on screen.
704  * \param[in] cloud the input point cloud dataset
705  * \param[in] color_handler the color handler to use
706  * \param[in] id the point cloud object id to update (default: cloud)
707  * \return false if no cloud with the specified ID was found
708  */
709  template <typename PointT> bool
710  updatePointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
711  const PointCloudColorHandler<PointT> &color_handler,
712  const std::string &id = "cloud");
713 
714  /** \brief Add a Point Cloud (templated) to screen.
715  * \param[in] cloud the input point cloud dataset
716  * \param[in] geometry_handler use a geometry handler object to extract the XYZ data
717  * \param[in] id the point cloud object id (default: cloud)
718  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
719  */
720  template <typename PointT> bool
721  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
722  const PointCloudGeometryHandler<PointT> &geometry_handler,
723  const std::string &id = "cloud", int viewport = 0);
724 
725  /** \brief Add a Point Cloud (templated) to screen.
726  *
727  * Because the geometry handler is given as a pointer, it will be pushed back to the list of available
728  * handlers, rather than replacing the current active geometric handler. This makes it possible to
729  * switch between different geometric handlers 'on-the-fly' at runtime, from the PCLVisualizer
730  * interactor interface (using Alt+0..9).
731  *
732  * \param[in] cloud the input point cloud dataset
733  * \param[in] geometry_handler use a geometry handler object to extract the XYZ data
734  * \param[in] id the point cloud object id (default: cloud)
735  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
736  */
737  template <typename PointT> bool
738  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
739  const GeometryHandlerConstPtr &geometry_handler,
740  const std::string &id = "cloud", int viewport = 0);
741 
742  /** \brief Add a Point Cloud (templated) to screen.
743  * \param[in] cloud the input point cloud dataset
744  * \param[in] color_handler a specific PointCloud visualizer handler for colors
745  * \param[in] id the point cloud object id (default: cloud)
746  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
747  */
748  template <typename PointT> bool
749  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
750  const PointCloudColorHandler<PointT> &color_handler,
751  const std::string &id = "cloud", int viewport = 0);
752 
753  /** \brief Add a Point Cloud (templated) to screen.
754  *
755  * Because the color handler is given as a pointer, it will be pushed back to the list of available
756  * handlers, rather than replacing the current active color handler. This makes it possible to
757  * switch between different color handlers 'on-the-fly' at runtime, from the PCLVisualizer
758  * interactor interface (using 0..9).
759  *
760  * \param[in] cloud the input point cloud dataset
761  * \param[in] color_handler a specific PointCloud visualizer handler for colors
762  * \param[in] id the point cloud object id (default: cloud)
763  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
764  */
765  template <typename PointT> bool
766  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
767  const ColorHandlerConstPtr &color_handler,
768  const std::string &id = "cloud", int viewport = 0);
769 
770  /** \brief Add a Point Cloud (templated) to screen.
771  *
772  * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of
773  * available handlers, rather than replacing the current active handler. This makes it possible to
774  * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor
775  * interface (using [Alt+]0..9).
776  *
777  * \param[in] cloud the input point cloud dataset
778  * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry
779  * \param[in] color_handler a specific PointCloud visualizer handler for colors
780  * \param[in] id the point cloud object id (default: cloud)
781  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
782  */
783  template <typename PointT> bool
784  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
785  const GeometryHandlerConstPtr &geometry_handler,
786  const ColorHandlerConstPtr &color_handler,
787  const std::string &id = "cloud", int viewport = 0);
788 
789  /** \brief Add a binary blob Point Cloud to screen.
790  *
791  * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of
792  * available handlers, rather than replacing the current active handler. This makes it possible to
793  * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor
794  * interface (using [Alt+]0..9).
795  *
796  * \param[in] cloud the input point cloud dataset
797  * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry
798  * \param[in] color_handler a specific PointCloud visualizer handler for colors
799  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
800  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
801  * \param[in] id the point cloud object id (default: cloud)
802  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
803  */
804  bool
806  const GeometryHandlerConstPtr &geometry_handler,
807  const ColorHandlerConstPtr &color_handler,
808  const Eigen::Vector4f& sensor_origin,
809  const Eigen::Quaternion<float>& sensor_orientation,
810  const std::string &id = "cloud", int viewport = 0);
811 
812  /** \brief Add a binary blob Point Cloud to screen.
813  *
814  * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of
815  * available handlers, rather than replacing the current active handler. This makes it possible to
816  * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor
817  * interface (using [Alt+]0..9).
818  *
819  * \param[in] cloud the input point cloud dataset
820  * \param[in] geometry_handler a specific PointCloud visualizer handler for geometry
821  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
822  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
823  * \param[in] id the point cloud object id (default: cloud)
824  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
825  */
826  bool
828  const GeometryHandlerConstPtr &geometry_handler,
829  const Eigen::Vector4f& sensor_origin,
830  const Eigen::Quaternion<float>& sensor_orientation,
831  const std::string &id = "cloud", int viewport = 0);
832 
833  /** \brief Add a binary blob Point Cloud to screen.
834  *
835  * Because the geometry/color handler is given as a pointer, it will be pushed back to the list of
836  * available handlers, rather than replacing the current active handler. This makes it possible to
837  * switch between different handlers 'on-the-fly' at runtime, from the PCLVisualizer interactor
838  * interface (using [Alt+]0..9).
839  *
840  * \param[in] cloud the input point cloud dataset
841  * \param[in] color_handler a specific PointCloud visualizer handler for colors
842  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
843  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
844  * \param[in] id the point cloud object id (default: cloud)
845  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
846  */
847  bool
849  const ColorHandlerConstPtr &color_handler,
850  const Eigen::Vector4f& sensor_origin,
851  const Eigen::Quaternion<float>& sensor_orientation,
852  const std::string &id = "cloud", int viewport = 0);
853 
854  /** \brief Add a Point Cloud (templated) to screen.
855  * \param[in] cloud the input point cloud dataset
856  * \param[in] color_handler a specific PointCloud visualizer handler for colors
857  * \param[in] geometry_handler use a geometry handler object to extract the XYZ data
858  * \param[in] id the point cloud object id (default: cloud)
859  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
860  */
861  template <typename PointT> bool
862  addPointCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
863  const PointCloudColorHandler<PointT> &color_handler,
864  const PointCloudGeometryHandler<PointT> &geometry_handler,
865  const std::string &id = "cloud", int viewport = 0);
866 
867  /** \brief Add a PointXYZ Point Cloud to screen.
868  * \param[in] cloud the input point cloud dataset
869  * \param[in] id the point cloud object id (default: cloud)
870  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
871  */
872  inline bool
874  const std::string &id = "cloud", int viewport = 0)
875  {
876  return (addPointCloud<pcl::PointXYZ> (cloud, id, viewport));
877  }
878 
879 
880  /** \brief Add a PointXYZRGB Point Cloud to screen.
881  * \param[in] cloud the input point cloud dataset
882  * \param[in] id the point cloud object id (default: cloud)
883  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
884  */
885  inline bool
887  const std::string &id = "cloud", int viewport = 0)
888  {
890  return (addPointCloud<pcl::PointXYZRGB> (cloud, color_handler, id, viewport));
891  }
892 
893  /** \brief Add a PointXYZRGBA Point Cloud to screen.
894  * \param[in] cloud the input point cloud dataset
895  * \param[in] id the point cloud object id (default: cloud)
896  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
897  */
898  inline bool
900  const std::string &id = "cloud", int viewport = 0)
901  {
903  return (addPointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id, viewport));
904  }
905 
906  /** \brief Add a PointXYZL Point Cloud to screen.
907  * \param[in] cloud the input point cloud dataset
908  * \param[in] id the point cloud object id (default: cloud)
909  * \param[in] viewport the view port where the Point Cloud should be added (default: all)
910  */
911  inline bool
913  const std::string &id = "cloud", int viewport = 0)
914  {
916  return (addPointCloud<pcl::PointXYZL> (cloud, color_handler, id, viewport));
917  }
918 
919  /** \brief Updates the XYZ data for an existing cloud object id on screen.
920  * \param[in] cloud the input point cloud dataset
921  * \param[in] id the point cloud object id to update (default: cloud)
922  * \return false if no cloud with the specified ID was found
923  */
924  inline bool
926  const std::string &id = "cloud")
927  {
928  return (updatePointCloud<pcl::PointXYZ> (cloud, id));
929  }
930 
931  /** \brief Updates the XYZRGB data for an existing cloud object id on screen.
932  * \param[in] cloud the input point cloud dataset
933  * \param[in] id the point cloud object id to update (default: cloud)
934  * \return false if no cloud with the specified ID was found
935  */
936  inline bool
938  const std::string &id = "cloud")
939  {
941  return (updatePointCloud<pcl::PointXYZRGB> (cloud, color_handler, id));
942  }
943 
944  /** \brief Updates the XYZRGBA data for an existing cloud object id on screen.
945  * \param[in] cloud the input point cloud dataset
946  * \param[in] id the point cloud object id to update (default: cloud)
947  * \return false if no cloud with the specified ID was found
948  */
949  inline bool
951  const std::string &id = "cloud")
952  {
954  return (updatePointCloud<pcl::PointXYZRGBA> (cloud, color_handler, id));
955  }
956 
957  /** \brief Updates the XYZL data for an existing cloud object id on screen.
958  * \param[in] cloud the input point cloud dataset
959  * \param[in] id the point cloud object id to update (default: cloud)
960  * \return false if no cloud with the specified ID was found
961  */
962  inline bool
964  const std::string &id = "cloud")
965  {
967  return (updatePointCloud<pcl::PointXYZL> (cloud, color_handler, id));
968  }
969 
970  /** \brief Add a PolygonMesh object to screen
971  * \param[in] polymesh the polygonal mesh
972  * \param[in] id the polygon object id (default: "polygon")
973  * \param[in] viewport the view port where the PolygonMesh should be added (default: all)
974  */
975  bool
977  const std::string &id = "polygon",
978  int viewport = 0);
979 
980  /** \brief Add a PolygonMesh object to screen
981  * \param[in] cloud the polygonal mesh point cloud
982  * \param[in] vertices the polygonal mesh vertices
983  * \param[in] id the polygon object id (default: "polygon")
984  * \param[in] viewport the view port where the PolygonMesh should be added (default: all)
985  */
986  template <typename PointT> bool
987  addPolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
988  const std::vector<pcl::Vertices> &vertices,
989  const std::string &id = "polygon",
990  int viewport = 0);
991 
992  /** \brief Update a PolygonMesh object on screen
993  * \param[in] cloud the polygonal mesh point cloud
994  * \param[in] vertices the polygonal mesh vertices
995  * \param[in] id the polygon object id (default: "polygon")
996  * \return false if no polygonmesh with the specified ID was found
997  */
998  template <typename PointT> bool
999  updatePolygonMesh (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
1000  const std::vector<pcl::Vertices> &vertices,
1001  const std::string &id = "polygon");
1002 
1003  /** \brief Update a PolygonMesh object on screen
1004  * \param[in] polymesh the polygonal mesh
1005  * \param[in] id the polygon object id (default: "polygon")
1006  * \return false if no polygonmesh with the specified ID was found
1007  */
1008  bool
1010  const std::string &id = "polygon");
1011 
1012  /** \brief Add a Polygonline from a polygonMesh object to screen
1013  * \param[in] polymesh the polygonal mesh from where the polylines will be extracted
1014  * \param[in] id the polygon object id (default: "polygon")
1015  * \param[in] viewport the view port where the PolygonMesh should be added (default: all)
1016  */
1017  bool
1019  const std::string &id = "polyline",
1020  int viewport = 0);
1021 
1022  /** \brief Add the specified correspondences to the display.
1023  * \param[in] source_points The source points
1024  * \param[in] target_points The target points
1025  * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points
1026  * \param[in] id the polygon object id (default: "correspondences")
1027  * \param[in] viewport the view port where the correspondences should be added (default: all)
1028  */
1029  template <typename PointT> bool
1030  addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
1031  const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
1032  const std::vector<int> & correspondences,
1033  const std::string &id = "correspondences",
1034  int viewport = 0);
1035 
1036  /** \brief Add a TextureMesh object to screen
1037  * \param[in] polymesh the textured polygonal mesh
1038  * \param[in] id the texture mesh object id (default: "texture")
1039  * \param[in] viewport the view port where the TextureMesh should be added (default: all)
1040  */
1041  bool
1043  const std::string &id = "texture",
1044  int viewport = 0);
1045 
1046  /** \brief Add the specified correspondences to the display.
1047  * \param[in] source_points The source points
1048  * \param[in] target_points The target points
1049  * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points
1050  * \param[in] nth display only the Nth correspondence (e.g., skip the rest)
1051  * \param[in] id the polygon object id (default: "correspondences")
1052  * \param[in] viewport the view port where the correspondences should be added (default: all)
1053  * \param[in] overwrite allow to overwrite already existing correspondences
1054  */
1055  template <typename PointT> bool
1056  addCorrespondences (const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
1057  const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
1058  const pcl::Correspondences &correspondences,
1059  int nth,
1060  const std::string &id = "correspondences",
1061  int viewport = 0,
1062  bool overwrite = false);
1063 
1064  /** \brief Add the specified correspondences to the display.
1065  * \param[in] source_points The source points
1066  * \param[in] target_points The target points
1067  * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points
1068  * \param[in] id the polygon object id (default: "correspondences")
1069  * \param[in] viewport the view port where the correspondences should be added (default: all)
1070  */
1071  template <typename PointT> bool
1073  const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
1074  const pcl::Correspondences &correspondences,
1075  const std::string &id = "correspondences",
1076  int viewport = 0)
1077  {
1078  // If Nth not given, display all correspondences
1079  return (addCorrespondences<PointT> (source_points, target_points,
1080  correspondences, 1, id, viewport));
1081  }
1082 
1083  /** \brief Update the specified correspondences to the display.
1084  * \param[in] source_points The source points
1085  * \param[in] target_points The target points
1086  * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points
1087  * \param[in] nth display only the Nth correspondence (e.g., skip the rest)
1088  * \param[in] id the polygon object id (default: "correspondences")
1089  * \param[in] viewport the view port where the correspondences should be updated (default: all)
1090  */
1091  template <typename PointT> bool
1092  updateCorrespondences (
1093  const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
1094  const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
1095  const pcl::Correspondences &correspondences,
1096  int nth,
1097  const std::string &id = "correspondences",
1098  int viewport = 0);
1099 
1100  /** \brief Update the specified correspondences to the display.
1101  * \param[in] source_points The source points
1102  * \param[in] target_points The target points
1103  * \param[in] correspondences The mapping from source points to target points. Each element must be an index into target_points
1104  * \param[in] id the polygon object id (default: "correspondences")
1105  * \param[in] viewport the view port where the correspondences should be updated (default: all)
1106  */
1107  template <typename PointT> bool
1109  const typename pcl::PointCloud<PointT>::ConstPtr &source_points,
1110  const typename pcl::PointCloud<PointT>::ConstPtr &target_points,
1111  const pcl::Correspondences &correspondences,
1112  const std::string &id = "correspondences",
1113  int viewport = 0)
1114  {
1115  // If Nth not given, display all correspondences
1116  return (updateCorrespondences<PointT> (source_points, target_points,
1117  correspondences, 1, id, viewport));
1118  }
1119 
1120  /** \brief Remove the specified correspondences from the display.
1121  * \param[in] id the polygon correspondences object id (i.e., given on \ref addCorrespondences)
1122  * \param[in] viewport view port from where the correspondences should be removed (default: all)
1123  */
1124  void
1125  removeCorrespondences (const std::string &id = "correspondences", int viewport = 0);
1126 
1127  /** \brief Get the color handler index of a rendered PointCloud based on its ID
1128  * \param[in] id the point cloud object id
1129  */
1130  int
1131  getColorHandlerIndex (const std::string &id);
1132 
1133  /** \brief Get the geometry handler index of a rendered PointCloud based on its ID
1134  * \param[in] id the point cloud object id
1135  */
1136  int
1137  getGeometryHandlerIndex (const std::string &id);
1138 
1139  /** \brief Update/set the color index of a rendered PointCloud based on its ID
1140  * \param[in] id the point cloud object id
1141  * \param[in] index the color handler index to use
1142  */
1143  bool
1144  updateColorHandlerIndex (const std::string &id, int index);
1145 
1146  /** \brief Set the rendering properties of a PointCloud (3x values - e.g., RGB)
1147  * \param[in] property the property type
1148  * \param[in] val1 the first value to be set
1149  * \param[in] val2 the second value to be set
1150  * \param[in] val3 the third value to be set
1151  * \param[in] id the point cloud object id (default: cloud)
1152  * \param[in] viewport the view port where the Point Cloud's rendering properties should be modified (default: all)
1153  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1154  */
1155  bool
1156  setPointCloudRenderingProperties (int property, double val1, double val2, double val3,
1157  const std::string &id = "cloud", int viewport = 0);
1158 
1159  /** \brief Set the rendering properties of a PointCloud (2x values - e.g., LUT minmax values)
1160  * \param[in] property the property type
1161  * \param[in] val1 the first value to be set
1162  * \param[in] val2 the second value to be set
1163  * \param[in] id the point cloud object id (default: cloud)
1164  * \param[in] viewport the view port where the Point Cloud's rendering properties should be modified (default: all)
1165  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1166  */
1167  bool
1168  setPointCloudRenderingProperties (int property, double val1, double val2,
1169  const std::string &id = "cloud", int viewport = 0);
1170 
1171  /** \brief Set the rendering properties of a PointCloud
1172  * \param[in] property the property type
1173  * \param[in] value the value to be set
1174  * \param[in] id the point cloud object id (default: cloud)
1175  * \param[in] viewport the view port where the Point Cloud's rendering properties should be modified (default: all)
1176  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1177  */
1178  bool
1179  setPointCloudRenderingProperties (int property, double value,
1180  const std::string &id = "cloud", int viewport = 0);
1181 
1182  /** \brief Get the rendering properties of a PointCloud
1183  * \param[in] property the property type
1184  * \param[in] value the resultant property value
1185  * \param[in] id the point cloud object id (default: cloud)
1186  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1187  */
1188  bool
1189  getPointCloudRenderingProperties (int property, double &value,
1190  const std::string &id = "cloud");
1191 
1192  /** \brief Get the rendering properties of a PointCloud
1193  * \param[in] property the property type
1194  * \param[out] val1 the resultant property value
1195  * \param[out] val2 the resultant property value
1196  * \param[out] val3 the resultant property value
1197  * \param[in] id the point cloud object id (default: cloud)
1198  * \return True if the property is effectively retrieved.
1199  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1200  */
1201  bool
1202  getPointCloudRenderingProperties (RenderingProperties property, double &val1, double &val2, double &val3,
1203  const std::string &id = "cloud");
1204 
1205  /** \brief Set whether the point cloud is selected or not
1206  * \param[in] selected whether the cloud is selected or not (true = selected)
1207  * \param[in] id the point cloud object id (default: cloud)
1208  */
1209  bool
1210  setPointCloudSelected (const bool selected, const std::string &id = "cloud" );
1211 
1212  /** \brief Set the rendering properties of a shape
1213  * \param[in] property the property type
1214  * \param[in] value the value to be set
1215  * \param[in] id the shape object id
1216  * \param[in] viewport the view port where the shape's properties should be modified (default: all)
1217  * \note When using \ref addPolygonMesh you you should use \ref setPointCloudRenderingProperties
1218  * \note The list of properties can be found in \ref pcl::visualization::LookUpTableRepresentationProperties.
1219  */
1220  bool
1221  setShapeRenderingProperties (int property, double value,
1222  const std::string &id, int viewport = 0);
1223 
1224  /** \brief Set the rendering properties of a shape (2x values - e.g., LUT minmax values)
1225  * \param[in] property the property type
1226  * \param[in] val1 the first value to be set
1227  * \param[in] val2 the second value to be set
1228  * \param[in] id the shape object id
1229  * \param[in] viewport the view port where the shape's properties should be modified (default: all)
1230  * \note When using \ref addPolygonMesh you you should use \ref setPointCloudRenderingProperties
1231  */
1232  bool
1233  setShapeRenderingProperties (int property, double val1, double val2,
1234  const std::string &id, int viewport = 0);
1235 
1236  /** \brief Set the rendering properties of a shape (3x values - e.g., RGB)
1237  * \param[in] property the property type
1238  * \param[in] val1 the first value to be set
1239  * \param[in] val2 the second value to be set
1240  * \param[in] val3 the third value to be set
1241  * \param[in] id the shape object id
1242  * \param[in] viewport the view port where the shape's properties should be modified (default: all)
1243  * \note When using \ref addPolygonMesh you you should use \ref setPointCloudRenderingProperties
1244  */
1245  bool
1246  setShapeRenderingProperties (int property, double val1, double val2, double val3,
1247  const std::string &id, int viewport = 0);
1248 
1249  /** \brief Returns true when the user tried to close the window */
1250  bool
1251  wasStopped () const;
1252 
1253  /** \brief Set the stopped flag back to false */
1254  void
1256 
1257  /** \brief Stop the interaction and close the visualization window. */
1258  void
1259  close ();
1260 
1261  /** \brief Create a new viewport from [xmin,ymin] -> [xmax,ymax].
1262  * \param[in] xmin the minimum X coordinate for the viewport (0.0 <= 1.0)
1263  * \param[in] ymin the minimum Y coordinate for the viewport (0.0 <= 1.0)
1264  * \param[in] xmax the maximum X coordinate for the viewport (0.0 <= 1.0)
1265  * \param[in] ymax the maximum Y coordinate for the viewport (0.0 <= 1.0)
1266  * \param[in] viewport the id of the new viewport
1267  *
1268  * \note If no renderer for the current window exists, one will be created, and
1269  * the viewport will be set to 0 ('all'). In case one or multiple renderers do
1270  * exist, the viewport ID will be set to the total number of renderers - 1.
1271  */
1272  void
1273  createViewPort (double xmin, double ymin, double xmax, double ymax, int &viewport);
1274 
1275  /** \brief Create a new separate camera for the given viewport.
1276  * \param[in] viewport the viewport to create a new camera for.
1277  */
1278  void
1279  createViewPortCamera (const int viewport);
1280 
1281  /** \brief Add a polygon (polyline) that represents the input point cloud (connects all
1282  * points in order)
1283  * \param[in] cloud the point cloud dataset representing the polygon
1284  * \param[in] r the red channel of the color that the polygon should be rendered with
1285  * \param[in] g the green channel of the color that the polygon should be rendered with
1286  * \param[in] b the blue channel of the color that the polygon should be rendered with
1287  * \param[in] id (optional) the polygon id/name (default: "polygon")
1288  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1289  */
1290  template <typename PointT> bool
1291  addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
1292  double r, double g, double b,
1293  const std::string &id = "polygon", int viewport = 0);
1294 
1295  /** \brief Add a polygon (polyline) that represents the input point cloud (connects all
1296  * points in order)
1297  * \param[in] cloud the point cloud dataset representing the polygon
1298  * \param[in] id the polygon id/name (default: "polygon")
1299  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1300  */
1301  template <typename PointT> bool
1302  addPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
1303  const std::string &id = "polygon",
1304  int viewport = 0);
1305 
1306  /** \brief Add a planar polygon that represents the input point cloud (connects all points in order)
1307  * \param[in] polygon the polygon to draw
1308  * \param[in] r the red channel of the color that the polygon should be rendered with
1309  * \param[in] g the green channel of the color that the polygon should be rendered with
1310  * \param[in] b the blue channel of the color that the polygon should be rendered with
1311  * \param[in] id the polygon id/name (default: "polygon")
1312  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1313  */
1314  template <typename PointT> bool
1315  addPolygon (const pcl::PlanarPolygon<PointT> &polygon,
1316  double r, double g, double b,
1317  const std::string &id = "polygon",
1318  int viewport = 0);
1319 
1320  /** \brief Add a line segment from two points
1321  * \param[in] pt1 the first (start) point on the line
1322  * \param[in] pt2 the second (end) point on the line
1323  * \param[in] id the line id/name (default: "line")
1324  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1325  */
1326  template <typename P1, typename P2> bool
1327  addLine (const P1 &pt1, const P2 &pt2, const std::string &id = "line",
1328  int viewport = 0);
1329 
1330  /** \brief Add a line segment from two points
1331  * \param[in] pt1 the first (start) point on the line
1332  * \param[in] pt2 the second (end) point on the line
1333  * \param[in] r the red channel of the color that the line should be rendered with
1334  * \param[in] g the green channel of the color that the line should be rendered with
1335  * \param[in] b the blue channel of the color that the line should be rendered with
1336  * \param[in] id the line id/name (default: "line")
1337  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1338  */
1339  template <typename P1, typename P2> bool
1340  addLine (const P1 &pt1, const P2 &pt2, double r, double g, double b,
1341  const std::string &id = "line", int viewport = 0);
1342 
1343  /** \brief Add a line arrow segment between two points, and display the distance between them
1344  *
1345  * Arrow heads are attached to both end points of the arrow.
1346  *
1347  * \param[in] pt1 the first (start) point on the line
1348  * \param[in] pt2 the second (end) point on the line
1349  * \param[in] r the red channel of the color that the line should be rendered with
1350  * \param[in] g the green channel of the color that the line should be rendered with
1351  * \param[in] b the blue channel of the color that the line should be rendered with
1352  * \param[in] id the arrow id/name (default: "arrow")
1353  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1354  */
1355  template <typename P1, typename P2> bool
1356  addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b,
1357  const std::string &id = "arrow", int viewport = 0);
1358 
1359  /** \brief Add a line arrow segment between two points, and (optionally) display the distance between them
1360  *
1361  * Arrow head is attached on the **start** point (\c pt1) of the arrow.
1362  *
1363  * \param[in] pt1 the first (start) point on the line
1364  * \param[in] pt2 the second (end) point on the line
1365  * \param[in] r the red channel of the color that the line should be rendered with
1366  * \param[in] g the green channel of the color that the line should be rendered with
1367  * \param[in] b the blue channel of the color that the line should be rendered with
1368  * \param[in] display_length true if the length should be displayed on the arrow as text
1369  * \param[in] id the line id/name (default: "arrow")
1370  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1371  */
1372  template <typename P1, typename P2> bool
1373  addArrow (const P1 &pt1, const P2 &pt2, double r, double g, double b, bool display_length,
1374  const std::string &id = "arrow", int viewport = 0);
1375 
1376  /** \brief Add a line arrow segment between two points, and display the distance between them in a given color
1377  *
1378  * Arrow heads are attached to both end points of the arrow.
1379  *
1380  * \param[in] pt1 the first (start) point on the line
1381  * \param[in] pt2 the second (end) point on the line
1382  * \param[in] r_line the red channel of the color that the line should be rendered with
1383  * \param[in] g_line the green channel of the color that the line should be rendered with
1384  * \param[in] b_line the blue channel of the color that the line should be rendered with
1385  * \param[in] r_text the red channel of the color that the text should be rendered with
1386  * \param[in] g_text the green channel of the color that the text should be rendered with
1387  * \param[in] b_text the blue channel of the color that the text should be rendered with
1388  * \param[in] id the line id/name (default: "arrow")
1389  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1390  */
1391  template <typename P1, typename P2> bool
1392  addArrow (const P1 &pt1, const P2 &pt2,
1393  double r_line, double g_line, double b_line,
1394  double r_text, double g_text, double b_text,
1395  const std::string &id = "arrow", int viewport = 0);
1396 
1397 
1398  /** \brief Add a sphere shape from a point and a radius
1399  * \param[in] center the center of the sphere
1400  * \param[in] radius the radius of the sphere
1401  * \param[in] id the sphere id/name (default: "sphere")
1402  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1403  */
1404  template <typename PointT> bool
1405  addSphere (const PointT &center, double radius, const std::string &id = "sphere",
1406  int viewport = 0);
1407 
1408  /** \brief Add a sphere shape from a point and a radius
1409  * \param[in] center the center of the sphere
1410  * \param[in] radius the radius of the sphere
1411  * \param[in] r the red channel of the color that the sphere should be rendered with
1412  * \param[in] g the green channel of the color that the sphere should be rendered with
1413  * \param[in] b the blue channel of the color that the sphere should be rendered with
1414  * \param[in] id the sphere id/name (default: "sphere")
1415  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1416  */
1417  template <typename PointT> bool
1418  addSphere (const PointT &center, double radius, double r, double g, double b,
1419  const std::string &id = "sphere", int viewport = 0);
1420 
1421  /** \brief Update an existing sphere shape from a point and a radius
1422  * \param[in] center the center of the sphere
1423  * \param[in] radius the radius of the sphere
1424  * \param[in] r the red channel of the color that the sphere should be rendered with
1425  * \param[in] g the green channel of the color that the sphere should be rendered with
1426  * \param[in] b the blue channel of the color that the sphere should be rendered with
1427  * \param[in] id the sphere id/name (default: "sphere")
1428  */
1429  template <typename PointT> bool
1430  updateSphere (const PointT &center, double radius, double r, double g, double b,
1431  const std::string &id = "sphere");
1432 
1433  /** \brief Add a vtkPolydata as a mesh
1434  * \param[in] polydata vtkPolyData
1435  * \param[in] id the model id/name (default: "PolyData")
1436  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1437  */
1438  bool
1440  const std::string & id = "PolyData",
1441  int viewport = 0);
1442 
1443  /** \brief Add a vtkPolydata as a mesh
1444  * \param[in] polydata vtkPolyData
1445  * \param[in] transform transformation to apply
1446  * \param[in] id the model id/name (default: "PolyData")
1447  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1448  */
1449  bool
1452  const std::string &id = "PolyData",
1453  int viewport = 0);
1454 
1455  /** \brief Add a PLYmodel as a mesh
1456  * \param[in] filename of the ply file
1457  * \param[in] id the model id/name (default: "PLYModel")
1458  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1459  */
1460  bool
1461  addModelFromPLYFile (const std::string &filename,
1462  const std::string &id = "PLYModel",
1463  int viewport = 0);
1464 
1465  /** \brief Add a PLYmodel as a mesh and applies given transformation
1466  * \param[in] filename of the ply file
1467  * \param[in] transform transformation to apply
1468  * \param[in] id the model id/name (default: "PLYModel")
1469  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1470  */
1471  bool
1472  addModelFromPLYFile (const std::string &filename,
1474  const std::string &id = "PLYModel",
1475  int viewport = 0);
1476 
1477  /** \brief Add a cylinder from a set of given model coefficients
1478  * \param[in] coefficients the model coefficients (point_on_axis, axis_direction, radius)
1479  * \param[in] id the cylinder id/name (default: "cylinder")
1480  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1481  *
1482  * \code
1483  * // The following are given (or computed using sample consensus techniques)
1484  * // See SampleConsensusModelCylinder for more information.
1485  * // Eigen::Vector3f pt_on_axis, axis_direction;
1486  * // float radius;
1487  *
1488  * pcl::ModelCoefficients cylinder_coeff;
1489  * cylinder_coeff.values.resize (7); // We need 7 values
1490  * cylinder_coeff.values[0] = pt_on_axis.x ();
1491  * cylinder_coeff.values[1] = pt_on_axis.y ();
1492  * cylinder_coeff.values[2] = pt_on_axis.z ();
1493  *
1494  * cylinder_coeff.values[3] = axis_direction.x ();
1495  * cylinder_coeff.values[4] = axis_direction.y ();
1496  * cylinder_coeff.values[5] = axis_direction.z ();
1497  *
1498  * cylinder_coeff.values[6] = radius;
1499  *
1500  * addCylinder (cylinder_coeff);
1501  * \endcode
1502  */
1503  bool
1504  addCylinder (const pcl::ModelCoefficients &coefficients,
1505  const std::string &id = "cylinder",
1506  int viewport = 0);
1507 
1508  /** \brief Add a sphere from a set of given model coefficients
1509  * \param[in] coefficients the model coefficients (sphere center, radius)
1510  * \param[in] id the sphere id/name (default: "sphere")
1511  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1512  *
1513  * \code
1514  * // The following are given (or computed using sample consensus techniques)
1515  * // See SampleConsensusModelSphere for more information
1516  * // Eigen::Vector3f sphere_center;
1517  * // float radius;
1518  *
1519  * pcl::ModelCoefficients sphere_coeff;
1520  * sphere_coeff.values.resize (4); // We need 4 values
1521  * sphere_coeff.values[0] = sphere_center.x ();
1522  * sphere_coeff.values[1] = sphere_center.y ();
1523  * sphere_coeff.values[2] = sphere_center.z ();
1524  *
1525  * sphere_coeff.values[3] = radius;
1526  *
1527  * addSphere (sphere_coeff);
1528  * \endcode
1529  */
1530  bool
1531  addSphere (const pcl::ModelCoefficients &coefficients,
1532  const std::string &id = "sphere",
1533  int viewport = 0);
1534 
1535  /** \brief Add a line from a set of given model coefficients
1536  * \param[in] coefficients the model coefficients (point_on_line, direction)
1537  * \param[in] id the line id/name (default: "line")
1538  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1539  *
1540  * \code
1541  * // The following are given (or computed using sample consensus techniques)
1542  * // See SampleConsensusModelLine for more information
1543  * // Eigen::Vector3f point_on_line, line_direction;
1544  *
1545  * pcl::ModelCoefficients line_coeff;
1546  * line_coeff.values.resize (6); // We need 6 values
1547  * line_coeff.values[0] = point_on_line.x ();
1548  * line_coeff.values[1] = point_on_line.y ();
1549  * line_coeff.values[2] = point_on_line.z ();
1550  *
1551  * line_coeff.values[3] = line_direction.x ();
1552  * line_coeff.values[4] = line_direction.y ();
1553  * line_coeff.values[5] = line_direction.z ();
1554  *
1555  * addLine (line_coeff);
1556  * \endcode
1557  */
1558  bool
1559  addLine (const pcl::ModelCoefficients &coefficients,
1560  const std::string &id = "line",
1561  int viewport = 0);
1562 
1563  /** \brief Add a line from a set of given model coefficients
1564  * \param[in] coefficients the model coefficients (point_on_line, direction)
1565  * \param[in] id the line id/name (default: "line")
1566  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1567  *
1568  * \code
1569  * // The following are given (or computed using sample consensus techniques)
1570  * // See SampleConsensusModelLine for more information
1571  * // Eigen::Vector3f point_on_line, line_direction;
1572  *
1573  * pcl::ModelCoefficients line_coeff;
1574  * line_coeff.values.resize (6); // We need 6 values
1575  * line_coeff.values[0] = point_on_line.x ();
1576  * line_coeff.values[1] = point_on_line.y ();
1577  * line_coeff.values[2] = point_on_line.z ();
1578  *
1579  * line_coeff.values[3] = line_direction.x ();
1580  * line_coeff.values[4] = line_direction.y ();
1581  * line_coeff.values[5] = line_direction.z ();
1582  *
1583  * addLine (line_coeff);
1584  * \endcode
1585  */
1586  bool
1587  addLine (const pcl::ModelCoefficients &coefficients,
1588  const char *id = "line",
1589  int viewport = 0)
1590  {
1591  return addLine (coefficients, std::string (id), viewport);
1592  }
1593 
1594  /** \brief Add a plane from a set of given model coefficients
1595  * \param[in] coefficients the model coefficients (a, b, c, d with ax+by+cz+d=0)
1596  * \param[in] id the plane id/name (default: "plane")
1597  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1598  *
1599  * \code
1600  * // The following are given (or computed using sample consensus techniques)
1601  * // See SampleConsensusModelPlane for more information
1602  * // Eigen::Vector4f plane_parameters;
1603  *
1604  * pcl::ModelCoefficients plane_coeff;
1605  * plane_coeff.values.resize (4); // We need 4 values
1606  * plane_coeff.values[0] = plane_parameters.x ();
1607  * plane_coeff.values[1] = plane_parameters.y ();
1608  * plane_coeff.values[2] = plane_parameters.z ();
1609  * plane_coeff.values[3] = plane_parameters.w ();
1610  *
1611  * addPlane (plane_coeff);
1612  * \endcode
1613  */
1614  bool
1615  addPlane (const pcl::ModelCoefficients &coefficients,
1616  const std::string &id = "plane",
1617  int viewport = 0);
1618 
1619  bool
1620  addPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z,
1621  const std::string &id = "plane",
1622  int viewport = 0);
1623  /** \brief Add a circle from a set of given model coefficients
1624  * \param[in] coefficients the model coefficients (x, y, radius)
1625  * \param[in] id the circle id/name (default: "circle")
1626  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1627  *
1628  * \code
1629  * // The following are given (or computed using sample consensus techniques)
1630  * // See SampleConsensusModelCircle2D for more information
1631  * // float x, y, radius;
1632  *
1633  * pcl::ModelCoefficients circle_coeff;
1634  * circle_coeff.values.resize (3); // We need 3 values
1635  * circle_coeff.values[0] = x;
1636  * circle_coeff.values[1] = y;
1637  * circle_coeff.values[2] = radius;
1638  *
1639  * vtkSmartPointer<vtkDataSet> data = pcl::visualization::create2DCircle (circle_coeff, z);
1640  * \endcode
1641  */
1642  bool
1643  addCircle (const pcl::ModelCoefficients &coefficients,
1644  const std::string &id = "circle",
1645  int viewport = 0);
1646 
1647  /** \brief Add a cone from a set of given model coefficients
1648  * \param[in] coefficients the model coefficients (see \ref pcl::visualization::createCone)
1649  * \param[in] id the cone id/name (default: "cone")
1650  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1651  */
1652  bool
1653  addCone (const pcl::ModelCoefficients &coefficients,
1654  const std::string &id = "cone",
1655  int viewport = 0);
1656 
1657  /** \brief Add a cube from a set of given model coefficients
1658  * \param[in] coefficients the model coefficients (see \ref pcl::visualization::createCube)
1659  * \param[in] id the cube id/name (default: "cube")
1660  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1661  */
1662  bool
1663  addCube (const pcl::ModelCoefficients &coefficients,
1664  const std::string &id = "cube",
1665  int viewport = 0);
1666 
1667  /** \brief Add a cube from a set of given model coefficients
1668  * \param[in] translation a translation to apply to the cube from 0,0,0
1669  * \param[in] rotation a quaternion-based rotation to apply to the cube
1670  * \param[in] width the cube's width
1671  * \param[in] height the cube's height
1672  * \param[in] depth the cube's depth
1673  * \param[in] id the cube id/name (default: "cube")
1674  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1675  */
1676  bool
1677  addCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
1678  double width, double height, double depth,
1679  const std::string &id = "cube",
1680  int viewport = 0);
1681 
1682  /** \brief Add a cube
1683  * \param[in] x_min the min X coordinate
1684  * \param[in] x_max the max X coordinate
1685  * \param[in] y_min the min Y coordinate
1686  * \param[in] y_max the max Y coordinate
1687  * \param[in] z_min the min Z coordinate
1688  * \param[in] z_max the max Z coordinate
1689  * \param[in] r how much red (0.0 -> 1.0)
1690  * \param[in] g how much green (0.0 -> 1.0)
1691  * \param[in] b how much blue (0.0 -> 1.0)
1692  * \param[in] id the cube id/name (default: "cube")
1693  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1694  */
1695  bool
1696  addCube (float x_min, float x_max, float y_min, float y_max, float z_min, float z_max,
1697  double r = 1.0, double g = 1.0, double b = 1.0, const std::string &id = "cube", int viewport = 0);
1698 
1699  /** \brief Add an ellipsoid from the given parameters
1700  * \param[in] transform a transformation to apply to the ellipsoid from 0,0,0
1701  * \param[in] radius_x the ellipsoid's radius along its local x-axis
1702  * \param[in] radius_y the ellipsoid's radius along its local y-axis
1703  * \param[in] radius_z the ellipsoid's radius along its local z-axis
1704  * \param[in] id the ellipsoid id/name (default: "ellipsoid")
1705  * \param[in] viewport (optional) the id of the new viewport (default: 0)
1706  */
1707  bool
1708  addEllipsoid (const Eigen::Isometry3d &transform,
1709  double radius_x, double radius_y, double radius_z,
1710  const std::string &id = "ellipsoid",
1711  int viewport = 0);
1712 
1713  /**
1714  * @brief Eye-Dome Lighting makes dark areas to improve depth perception
1715  * See https://www.kitware.com/eye-dome-lighting-a-non-photorealistic-shading-technique/
1716  * It is applied to all actors, including texts.
1717  * @param viewport
1718  */
1719  void
1720  enableEDLRendering(int viewport = 0);
1721 
1722  /** \brief Changes the visual representation for all actors to surface representation. */
1723  void
1725 
1726  /** \brief Changes the visual representation for all actors to points representation. */
1727  void
1729 
1730  /** \brief Changes the visual representation for all actors to wireframe representation. */
1731  void
1733 
1734  /** \brief Sets whether the 2D overlay text showing the framerate of the window is displayed or not.
1735  * \param[in] show_fps determines whether the fps text will be shown or not.
1736  */
1737  void
1738  setShowFPS (bool show_fps);
1739 
1740  /** Get the current rendering framerate.
1741  * \see setShowFPS */
1742  float
1743  getFPS () const;
1744 
1745  /** \brief Renders a virtual scene as seen from the camera viewpoint and returns the rendered point cloud.
1746  * ATT: This method will only render the scene if only on viewport exists. Otherwise, returns an empty
1747  * point cloud and exits immediately.
1748  * \param[in] xres is the size of the window (X) used to render the scene
1749  * \param[in] yres is the size of the window (Y) used to render the scene
1750  * \param[in] cloud is the rendered point cloud
1751  */
1752  void
1753  renderView (int xres, int yres, pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
1754 
1755  /** \brief The purpose of this method is to render a CAD model added to the visualizer from different viewpoints
1756  * in order to simulate partial views of model. The viewpoint locations are the vertices of a tessellated sphere
1757  * build from an icosaheadron. The tessellation parameter controls how many times the triangles of the original
1758  * icosahedron are divided to approximate the sphere and thus the number of partial view generated for a model,
1759  * with a tesselation_level of 0, 12 views are generated if use_vertices=true and 20 views if use_vertices=false
1760  *
1761  * \param[in] xres the size of the window (X) used to render the partial view of the object
1762  * \param[in] yres the size of the window (Y) used to render the partial view of the object
1763  * \param[in] cloud is a vector of pointcloud with XYZ information that represent the model as seen from the respective viewpoints.
1764  * \param[out] poses represent the transformation from object coordinates to camera coordinates for the respective viewpoint.
1765  * \param[out] enthropies are values between 0 and 1 representing which percentage of the model is seen from the respective viewpoint.
1766  * \param[in] tesselation_level represents the number of subdivisions applied to the triangles of original icosahedron.
1767  * \param[in] view_angle field of view of the virtual camera. Default: 45
1768  * \param[in] radius_sphere the tessellated sphere radius. Default: 1
1769  * \param[in] use_vertices if true, use the vertices of tessellated icosahedron (12,42,...) or if false, use the faces of tessellated
1770  * icosahedron (20,80,...). Default: true
1771  */
1772  void
1774  int xres, int yres,
1776  std::vector<Eigen::Matrix4f,Eigen::aligned_allocator< Eigen::Matrix4f > > & poses, std::vector<float> & enthropies, int tesselation_level,
1777  float view_angle = 45, float radius_sphere = 1, bool use_vertices = true);
1778 
1779 
1780  /** \brief Initialize camera parameters with some default values. */
1781  void
1783 
1784  /** \brief Search for camera parameters at the command line and set them internally.
1785  * \param[in] argc
1786  * \param[in] argv
1787  */
1788  bool
1789  getCameraParameters (int argc, char **argv);
1790 
1791  /** \brief Load camera parameters from a camera parameters file.
1792  * \param[in] file the name of the camera parameters file
1793  */
1794  bool
1795  loadCameraParameters (const std::string &file);
1796 
1797  /** \brief Checks whether the camera parameters were manually loaded.
1798  * \return True if valid "-cam" option is available in command line.
1799  * \sa cameraFileLoaded ()
1800  */
1801  bool
1803 
1804  /** \brief Checks whether a camera file were automatically loaded.
1805  * \return True if a valid camera file is automatically loaded.
1806  * \note The camera file is saved by pressing "ctrl + s" during last run of the program
1807  * and restored automatically when the program runs this time.
1808  * \sa cameraParamsSet ()
1809  */
1810  bool
1812 
1813  /** \brief Get camera file for camera parameter saving/restoring.
1814  * \note This will be valid only when valid "-cam" option were available in command line
1815  * or a saved camera file were automatically loaded.
1816  * \sa cameraParamsSet (), cameraFileLoaded ()
1817  */
1818  std::string
1819  getCameraFile () const;
1820 
1821  /** \brief Reset camera parameters and render. */
1822  void
1824 
1825  /** \brief Reset the camera direction from {0, 0, 0} to the center_{x, y, z} of a given dataset.
1826  * \param[in] id the point cloud object id (default: cloud)
1827  */
1828  void
1829  resetCameraViewpoint (const std::string &id = "cloud");
1830 
1831  /** \brief Set the camera pose given by position, viewpoint and up vector
1832  * \param[in] pos_x the x coordinate of the camera location
1833  * \param[in] pos_y the y coordinate of the camera location
1834  * \param[in] pos_z the z coordinate of the camera location
1835  * \param[in] view_x the x component of the view point of the camera
1836  * \param[in] view_y the y component of the view point of the camera
1837  * \param[in] view_z the z component of the view point of the camera
1838  * \param[in] up_x the x component of the view up direction of the camera
1839  * \param[in] up_y the y component of the view up direction of the camera
1840  * \param[in] up_z the z component of the view up direction of the camera
1841  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1842  */
1843  void
1844  setCameraPosition (double pos_x, double pos_y, double pos_z,
1845  double view_x, double view_y, double view_z,
1846  double up_x, double up_y, double up_z, int viewport = 0);
1847 
1848  /** \brief Set the camera location and viewup according to the given arguments
1849  * \param[in] pos_x the x coordinate of the camera location
1850  * \param[in] pos_y the y coordinate of the camera location
1851  * \param[in] pos_z the z coordinate of the camera location
1852  * \param[in] up_x the x component of the view up direction of the camera
1853  * \param[in] up_y the y component of the view up direction of the camera
1854  * \param[in] up_z the z component of the view up direction of the camera
1855  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1856  */
1857  void
1858  setCameraPosition (double pos_x, double pos_y, double pos_z,
1859  double up_x, double up_y, double up_z, int viewport = 0);
1860 
1861  /** \brief Set the camera parameters via an intrinsics and and extrinsics matrix
1862  * \note This assumes that the pixels are square and that the center of the image is at the center of the sensor.
1863  * \param[in] intrinsics the intrinsics that will be used to compute the VTK camera parameters
1864  * \param[in] extrinsics the extrinsics that will be used to compute the VTK camera parameters
1865  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1866  */
1867  void
1868  setCameraParameters (const Eigen::Matrix3f &intrinsics, const Eigen::Matrix4f &extrinsics, int viewport = 0);
1869 
1870  /** \brief Set the camera parameters by given a full camera data structure.
1871  * \param[in] camera camera structure containing all the camera parameters.
1872  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1873  */
1874  void
1875  setCameraParameters (const Camera &camera, int viewport = 0);
1876 
1877  /** \brief Set the camera clipping distances.
1878  * \param[in] near the near clipping distance (no objects closer than this to the camera will be drawn)
1879  * \param[in] far the far clipping distance (no objects further away than this to the camera will be drawn)
1880  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1881  */
1882  void
1883  setCameraClipDistances (double near, double far, int viewport = 0);
1884 
1885  /** \brief Set the camera vertical field of view.
1886  * \param[in] fovy vertical field of view in radians
1887  * \param[in] viewport the viewport to modify camera of (0 modifies all cameras)
1888  */
1889  void
1890  setCameraFieldOfView (double fovy, int viewport = 0);
1891 
1892  /** \brief Get the current camera parameters. */
1893  void
1894  getCameras (std::vector<Camera>& cameras);
1895 
1896 
1897  /** \brief Get the current viewing pose. */
1898  Eigen::Affine3f
1899  getViewerPose (int viewport = 0);
1900 
1901  /** \brief Save the current rendered image to disk, as a PNG screenshot.
1902  * \param[in] file the name of the PNG file
1903  */
1904  void
1905  saveScreenshot (const std::string &file);
1906 
1907  /** \brief Save the camera parameters to disk, as a .cam file.
1908  * \param[in] file the name of the .cam file
1909  */
1910  void
1911  saveCameraParameters (const std::string &file);
1912 
1913  /** \brief Get camera parameters of a given viewport (0 means default viewport). */
1914  void
1915  getCameraParameters (Camera &camera, int viewport = 0) const;
1916 
1917  /** \brief Return a pointer to the underlying VTK Render Window used. */
1920  {
1921  return (win_);
1922  }
1923 
1924  /** \brief Return a pointer to the underlying VTK Renderer Collection. */
1927  {
1928  return (rens_);
1929  }
1930 
1931  /** \brief Return a pointer to the CloudActorMap this visualizer uses. */
1934  {
1935  return (cloud_actor_map_);
1936  }
1937 
1938  /** \brief Return a pointer to the ShapeActorMap this visualizer uses. */
1941  {
1942  return (shape_actor_map_);
1943  }
1944 
1945  /** \brief Set the position in screen coordinates.
1946  * \param[in] x where to move the window to (X)
1947  * \param[in] y where to move the window to (Y)
1948  */
1949  void
1950  setPosition (int x, int y);
1951 
1952  /** \brief Set the window size in screen coordinates.
1953  * \param[in] xw window size in horizontal (pixels)
1954  * \param[in] yw window size in vertical (pixels)
1955  */
1956  void
1957  setSize (int xw, int yw);
1958 
1959  /** \brief Use Vertex Buffer Objects renderers.
1960  * This is an optimization for the obsolete OpenGL backend. Modern OpenGL2 backend (VTK ≥ 6.3) uses vertex
1961  * buffer objects by default, transparently for the user.
1962  * \param[in] use_vbos set to true to use VBOs
1963  */
1964  PCL_DEPRECATED(1, 18, "this function has no effect")
1965  void
1966  setUseVbos (bool use_vbos);
1967 
1968  /** \brief Set the ID of a cloud or shape to be used for LUT display
1969  * \param[in] id The id of the cloud/shape look up table to be displayed
1970  * The look up table is displayed by pressing 'u' in the PCLVisualizer */
1971  void
1972  setLookUpTableID (const std::string id);
1973 
1974  /** \brief Create the internal Interactor object. */
1975  void
1976  createInteractor ();
1977 
1978  /** \brief Set up our unique PCL interactor style for a given vtkRenderWindowInteractor object
1979  * attached to a given vtkRenderWindow
1980  * \param[in,out] iren the vtkRenderWindowInteractor object to set up
1981  * \param[in,out] win a vtkRenderWindow object that the interactor is attached to
1982  */
1983  void
1984  setupInteractor (vtkRenderWindowInteractor *iren,
1985  vtkRenderWindow *win);
1986 
1987  /** \brief Set up PCLVisualizer with custom interactor style for a given vtkRenderWindowInteractor object
1988  * attached to a given vtkRenderWindow
1989  * \param[in,out] iren the vtkRenderWindowInteractor object to set up
1990  * \param[in,out] win a vtkRenderWindow object that the interactor is attached to
1991  * \param[in,out] style a vtkInteractorStyle object
1992  */
1993  void
1994  setupInteractor (vtkRenderWindowInteractor *iren,
1995  vtkRenderWindow *win,
1996  vtkInteractorStyle *style);
1997 
1998  /** \brief Get a pointer to the current interactor style used. */
2000  getInteractorStyle ()
2001  {
2002  return (style_);
2003  }
2004  protected:
2005  /** \brief The render window interactor. */
2007  private:
2008  /** \brief Internal function for renderer setup
2009  * \param[in] vtk renderer
2010  */
2011  void setupRenderer (vtkSmartPointer<vtkRenderer> ren);
2012 
2013  /** \brief Internal function for setting up FPS callback
2014  * \param[in] vtk renderer
2015  */
2016  void setupFPSCallback (const vtkSmartPointer<vtkRenderer>& ren);
2017 
2018  /** \brief Internal function for setting up render window
2019  * \param[in] name the window name
2020  */
2021  void setupRenderWindow (const std::string& name);
2022 
2023  /** \brief Internal function for setting up interactor style
2024  */
2025  void setupStyle ();
2026 
2027  /** \brief Internal function for setting the default render window size and position on screen
2028  */
2029  void setDefaultWindowSizeAndPos ();
2030 
2031  /** \brief Set up camera parameters.
2032  *
2033  * Parses command line arguments to find camera parameters (either explicit numbers or a path to a .cam file).
2034  * If not found, will generate a unique .cam file path (based on the rest of command line arguments) and try
2035  * to load that. If it is also not found, just set the defaults.
2036  */
2037  void setupCamera (int argc, char **argv);
2038 
2039  struct PCL_EXPORTS ExitMainLoopTimerCallback : public vtkCommand
2040  {
2041  static ExitMainLoopTimerCallback* New ()
2042  {
2043  return (new ExitMainLoopTimerCallback);
2044  }
2045  void
2046  Execute (vtkObject*, unsigned long event_id, void*) override;
2047 
2048  int right_timer_id;
2049  PCLVisualizer* pcl_visualizer;
2050  };
2051 
2052  struct PCL_EXPORTS ExitCallback : public vtkCommand
2053  {
2054  static ExitCallback* New ()
2055  {
2056  return (new ExitCallback);
2057  }
2058  void
2059  Execute (vtkObject*, unsigned long event_id, void*) override;
2060 
2061  PCLVisualizer* pcl_visualizer;
2062  };
2063 
2064  //////////////////////////////////////////////////////////////////////////////////////////////
2065  struct PCL_EXPORTS FPSCallback : public vtkCommand
2066  {
2067  static FPSCallback *New () { return (new FPSCallback); }
2068 
2069  FPSCallback () = default;
2070  FPSCallback (const FPSCallback& src) = default;
2071  FPSCallback& operator = (const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps; return (*this); }
2072 
2073  void
2074  Execute (vtkObject*, unsigned long event_id, void*) override;
2075 
2076  vtkTextActor *actor{nullptr};
2077  PCLVisualizer* pcl_visualizer{nullptr};
2078  bool decimated{false};
2079  float last_fps{0.0f};
2080  };
2081 
2082  /** \brief The FPSCallback object for the current visualizer. */
2083  vtkSmartPointer<FPSCallback> update_fps_;
2084 
2085  /** \brief Set to false if the interaction loop is running. */
2086  bool stopped_{false};
2087 
2088  /** \brief Global timer ID. Used in destructor only. */
2089  int timer_id_{0};
2090 
2091  /** \brief Callback object enabling us to leave the main loop, when a timer fires. */
2092  vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
2093  vtkSmartPointer<ExitCallback> exit_callback_;
2094 
2095  /** \brief The collection of renderers used. */
2097 
2098  /** \brief The render window. */
2100 
2101  /** \brief The render window interactor style. */
2103 
2104  /** \brief Internal list with actor pointers and name IDs for point clouds. */
2105  CloudActorMapPtr cloud_actor_map_;
2106 
2107  /** \brief Internal list with actor pointers and name IDs for shapes. */
2108  ShapeActorMapPtr shape_actor_map_;
2109 
2110  /** \brief Internal list with actor pointers and viewpoint for coordinates. */
2111  CoordinateActorMapPtr coordinate_actor_map_;
2112 
2113  /** \brief Internal pointer to widget which contains a set of axes */
2115 
2116  /** \brief Boolean that holds whether or not the camera parameters were manually initialized */
2117  bool camera_set_;
2118 
2119  /** \brief Boolean that holds whether or not a camera file were automatically loaded */
2120  bool camera_file_loaded_;
2121 
2122  /** \brief Boolean that holds whether or not to use the vtkVertexBufferObjectMapper*/
2123  bool use_vbos_;
2124 
2125  /** \brief Internal method. Removes a vtk actor from the screen.
2126  * \param[in] actor a pointer to the vtk actor object
2127  * \param[in] viewport the view port where the actor should be removed from (default: all)
2128  */
2129  bool
2130  removeActorFromRenderer (const vtkSmartPointer<vtkLODActor> &actor,
2131  int viewport = 0);
2132 
2133  /** \brief Internal method. Removes a vtk actor from the screen.
2134  * \param[in] actor a pointer to the vtk actor object
2135  * \param[in] viewport the view port where the actor should be removed from (default: all)
2136  */
2137  bool
2138  removeActorFromRenderer (const vtkSmartPointer<vtkActor> &actor,
2139  int viewport = 0);
2140 
2141  /** \brief Internal method. Adds a vtk actor to screen.
2142  * \param[in] actor a pointer to the vtk actor object
2143  * \param[in] viewport port where the actor should be added to (default: 0/all)
2144  *
2145  * \note If viewport is set to 0, the actor will be added to all existing
2146  * renders. To select a specific viewport use an integer between 1 and N.
2147  */
2148  void
2149  addActorToRenderer (const vtkSmartPointer<vtkProp> &actor,
2150  int viewport = 0);
2151 
2152  /** \brief Internal method. Adds a vtk actor to screen.
2153  * \param[in] actor a pointer to the vtk actor object
2154  * \param[in] viewport the view port where the actor should be added to (default: all)
2155  */
2156  bool
2157  removeActorFromRenderer (const vtkSmartPointer<vtkProp> &actor,
2158  int viewport = 0);
2159 
2160  /** \brief Internal method. Creates a vtk actor from a vtk polydata object.
2161  * \param[in] data the vtk polydata object to create an actor for
2162  * \param[out] actor the resultant vtk actor object
2163  * \param[in] use_scalars set scalar properties to the mapper if it exists in the data. Default: true.
2164  */
2165  void
2166  createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
2168  bool use_scalars = true) const;
2169 
2170  /** \brief Internal method. Creates a vtk actor from a vtk polydata object.
2171  * \param[in] data the vtk polydata object to create an actor for
2172  * \param[out] actor the resultant vtk actor object
2173  * \param[in] use_scalars set scalar properties to the mapper if it exists in the data. Default: true.
2174  */
2175  void
2176  createActorFromVTKDataSet (const vtkSmartPointer<vtkDataSet> &data,
2178  bool use_scalars = true) const;
2179 
2180  /** \brief Converts a PCL templated PointCloud object to a vtk polydata object.
2181  * \param[in] cloud the input PCL PointCloud dataset
2182  * \param[out] polydata the resultant polydata containing the cloud
2183  * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed
2184  * around to speed up the conversion.
2185  */
2186  template <typename PointT> void
2187  convertPointCloudToVTKPolyData (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
2188  vtkSmartPointer<vtkPolyData> &polydata,
2189  vtkSmartPointer<vtkIdTypeArray> &initcells);
2190 
2191  /** \brief Converts a PCL templated PointCloud object to a vtk polydata object.
2192  * \param[in] geometry_handler the geometry handler object used to extract the XYZ data
2193  * \param[out] polydata the resultant polydata containing the cloud
2194  * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed
2195  * around to speed up the conversion.
2196  */
2197  template <typename PointT> void
2198  convertPointCloudToVTKPolyData (const PointCloudGeometryHandler<PointT> &geometry_handler,
2199  vtkSmartPointer<vtkPolyData> &polydata,
2200  vtkSmartPointer<vtkIdTypeArray> &initcells);
2201 
2202  /** \brief Converts a PCL object to a vtk polydata object.
2203  * \param[in] geometry_handler the geometry handler object used to extract the XYZ data
2204  * \param[out] polydata the resultant polydata containing the cloud
2205  * \param[out] initcells a list of cell indices used for the conversion. This can be set once and then passed
2206  * around to speed up the conversion.
2207  */
2208  void
2209  convertPointCloudToVTKPolyData (const GeometryHandlerConstPtr &geometry_handler,
2210  vtkSmartPointer<vtkPolyData> &polydata,
2211  vtkSmartPointer<vtkIdTypeArray> &initcells);
2212 
2213  /** \brief Updates a set of cells (vtkIdTypeArray) if the number of points in a cloud changes
2214  * \param[out] cells the vtkIdTypeArray object (set of cells) to update
2215  * \param[out] initcells a previously saved set of cells. If the number of points in the current cloud is
2216  * higher than the number of cells in \a cells, and initcells contains enough data, then a copy from it
2217  * will be made instead of regenerating the entire array.
2218  * \param[in] nr_points the number of points in the new cloud. This dictates how many cells we need to
2219  * generate
2220  */
2221  void
2222  updateCells (vtkSmartPointer<vtkIdTypeArray> &cells,
2224  vtkIdType nr_points);
2225 
2226  /** \brief Internal function which converts the information present in the geometric
2227  * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds
2228  * all the required information to the internal cloud_actor_map_ object.
2229  * \param[in] geometry_handler the geometric handler that contains the XYZ data
2230  * \param[in] color_handler the color handler that contains the "RGB" (scalar) data
2231  * \param[in] id the point cloud object id
2232  * \param[in] viewport the view port where the Point Cloud should be added
2233  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
2234  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
2235  */
2236  template <typename PointT> bool
2237  fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
2238  const PointCloudColorHandler<PointT> &color_handler,
2239  const std::string &id,
2240  int viewport,
2241  const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2242  const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2243 
2244  /** \brief Internal function which converts the information present in the geometric
2245  * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds
2246  * all the required information to the internal cloud_actor_map_ object.
2247  * \param[in] geometry_handler the geometric handler that contains the XYZ data
2248  * \param[in] color_handler the color handler that contains the "RGB" (scalar) data
2249  * \param[in] id the point cloud object id
2250  * \param[in] viewport the view port where the Point Cloud should be added
2251  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
2252  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
2253  */
2254  template <typename PointT> bool
2255  fromHandlersToScreen (const PointCloudGeometryHandler<PointT> &geometry_handler,
2256  const ColorHandlerConstPtr &color_handler,
2257  const std::string &id,
2258  int viewport,
2259  const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2260  const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2261 
2262  /** \brief Internal function which converts the information present in the geometric
2263  * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds
2264  * all the required information to the internal cloud_actor_map_ object.
2265  * \param[in] geometry_handler the geometric handler that contains the XYZ data
2266  * \param[in] color_handler the color handler that contains the "RGB" (scalar) data
2267  * \param[in] id the point cloud object id
2268  * \param[in] viewport the view port where the Point Cloud should be added
2269  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
2270  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
2271  */
2272  bool
2273  fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
2274  const ColorHandlerConstPtr &color_handler,
2275  const std::string &id,
2276  int viewport,
2277  const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2278  const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2279 
2280  /** \brief Internal function which converts the information present in the geometric
2281  * and color handlers into VTK PolyData+Scalars, constructs a vtkActor object, and adds
2282  * all the required information to the internal cloud_actor_map_ object.
2283  * \param[in] geometry_handler the geometric handler that contains the XYZ data
2284  * \param[in] color_handler the color handler that contains the "RGB" (scalar) data
2285  * \param[in] id the point cloud object id
2286  * \param[in] viewport the view port where the Point Cloud should be added
2287  * \param[in] sensor_origin the origin of the cloud data in global coordinates (defaults to 0,0,0)
2288  * \param[in] sensor_orientation the orientation of the cloud data in global coordinates (defaults to 1,0,0,0)
2289  */
2290  template <typename PointT> bool
2291  fromHandlersToScreen (const GeometryHandlerConstPtr &geometry_handler,
2292  const PointCloudColorHandler<PointT> &color_handler,
2293  const std::string &id,
2294  int viewport,
2295  const Eigen::Vector4f& sensor_origin = Eigen::Vector4f (0, 0, 0, 0),
2296  const Eigen::Quaternion<float>& sensor_orientation = Eigen::Quaternion<float> (1, 0, 0 ,0));
2297 
2298  /** \brief Allocate a new polydata smartpointer. Internal
2299  * \param[out] polydata the resultant poly data
2300  */
2301  void
2302  allocVtkPolyData (vtkSmartPointer<vtkAppendPolyData> &polydata);
2303 
2304  /** \brief Allocate a new polydata smartpointer. Internal
2305  * \param[out] polydata the resultant poly data
2306  */
2307  void
2308  allocVtkPolyData (vtkSmartPointer<vtkPolyData> &polydata);
2309 
2310  /** \brief Allocate a new unstructured grid smartpointer. Internal
2311  * \param[out] polydata the resultant poly data
2312  */
2313  void
2315 
2316  /** \brief Transform the point cloud viewpoint to a transformation matrix
2317  * \param[in] origin the camera origin
2318  * \param[in] orientation the camera orientation
2319  * \param[out] transformation the camera transformation matrix
2320  */
2321  void
2322  getTransformationMatrix (const Eigen::Vector4f &origin,
2323  const Eigen::Quaternion<float> &orientation,
2324  Eigen::Matrix4f &transformation);
2325 
2326  /** \brief Fills a vtkTexture structure from pcl::TexMaterial.
2327  * \param[in] tex_mat texture material in PCL format
2328  * \param[out] vtk_tex texture material in VTK format
2329  * \return 0 on success and -1 else.
2330  * \note for now only image based textures are supported, image file must be in
2331  * tex_file attribute of \a tex_mat.
2332  */
2333  int
2334  textureFromTexMaterial (const pcl::TexMaterial& tex_mat,
2335  vtkTexture* vtk_tex) const;
2336 
2337  /** \brief Get camera file for camera parameter saving/restoring from command line.
2338  * Camera filename is calculated using sha1 value of all paths of input .pcd files
2339  * \return empty string if failed.
2340  */
2341  std::string
2342  getUniqueCameraFile (int argc, char **argv);
2343 
2344  //There's no reason these conversion functions shouldn't be public and static so others can use them.
2345  public:
2346  /** \brief Convert Eigen::Matrix4f to vtkMatrix4x4
2347  * \param[in] m the input Eigen matrix
2348  * \param[out] vtk_matrix the resultant VTK matrix
2349  */
2350  static void
2351  convertToVtkMatrix (const Eigen::Matrix4f &m,
2352  vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
2353 
2354  /** \brief Convert origin and orientation to vtkMatrix4x4
2355  * \param[in] origin the point cloud origin
2356  * \param[in] orientation the point cloud orientation
2357  * \param[out] vtk_matrix the resultant VTK 4x4 matrix
2358  */
2359  static void
2360  convertToVtkMatrix (const Eigen::Vector4f &origin,
2361  const Eigen::Quaternion<float> &orientation,
2362  vtkSmartPointer<vtkMatrix4x4> &vtk_matrix);
2363 
2364  /** \brief Convert vtkMatrix4x4 to an Eigen4f
2365  * \param[in] vtk_matrix the original VTK 4x4 matrix
2366  * \param[out] m the resultant Eigen 4x4 matrix
2367  */
2368  static void
2370  Eigen::Matrix4f &m);
2371 
2372  };
2373  }
2374 }
2375 
2376 #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.
Definition: point_cloud.h:173
std::vector< PointCloud< PointT >, Eigen::aligned_allocator< PointCloud< PointT > > > CloudVectorType
Definition: point_cloud.h:412
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
/brief Class representing 3D area picking events.
Camera class holds a set of camera parameters together with the window pos/size.
Definition: common.h:153
/brief Class representing key hit/release events
PCL Visualizer main class.
void close()
Stop the interaction and close the visualization 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.
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.
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.
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 enableEDLRendering(int viewport=0)
Eye-Dome Lighting makes dark areas to improve depth perception See https://www.kitware....
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.
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 setCameraClipDistances(double near, double far, int viewport=0)
Set the camera clipping distances.
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.
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 addEllipsoid(const Eigen::Isometry3d &transform, double radius_x, double radius_y, double radius_z, const std::string &id="ellipsoid", int viewport=0)
Add an ellipsoid from the given parameters.
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.
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()
shared_ptr< const PointCloudColorHandler< PointCloud > > ConstPtr
Base Handler class for PointCloud colors.
shared_ptr< const PointCloudGeometryHandler< PointCloud > > ConstPtr
Base handler class for PointCloud geometry.
/brief Class representing 3D point picking events.
PCL_EXPORTS vtkIdType fillCells(std::vector< int > &lookup, const std::vector< pcl::Vertices > &vertices, vtkSmartPointer< vtkCellArray > cell_array, int max_size_of_polygon)
RenderingProperties
Set of rendering properties.
Definition: common.h:102
shared_ptr< CloudActorMap > CloudActorMapPtr
Definition: actor_map.h:97
shared_ptr< ShapeActorMap > ShapeActorMapPtr
Definition: actor_map.h:100
shared_ptr< CoordinateActorMap > CoordinateActorMapPtr
Definition: actor_map.h:103
PCL_EXPORTS void allocVtkUnstructuredGrid(vtkSmartPointer< vtkUnstructuredGrid > &polydata)
Allocate a new unstructured grid smartpointer.
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
#define PCL_EXPORTS
Definition: pcl_macros.h:323
#define PCL_DEPRECATED(Major, Minor, Message)
macro for compatibility across compilers and help remove old deprecated items for the Major....
Definition: pcl_macros.h:156
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.