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