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