CloudViewer.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef RTABMAP_CLOUDVIEWER_H_
29 #define RTABMAP_CLOUDVIEWER_H_
30 
31 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
32 
33 #include "rtabmap/core/Transform.h"
36 
37 #if VTK_MAJOR_VERSION > 8
38 #ifndef slots
39 #define slots Q_SLOTS
40 #endif
41 #include <QVTKOpenGLNativeWidget.h>
42 using PCLQVTKWidget = QVTKOpenGLNativeWidget;
43 #else
44 #include <QVTKWidget.h>
45 using PCLQVTKWidget = QVTKWidget;
46 #endif
47 #include <pcl/pcl_base.h>
48 #include <pcl/point_types.h>
49 #include <pcl/point_cloud.h>
50 #include <pcl/PolygonMesh.h>
51 #include <pcl/TextureMesh.h>
52 
53 #include <QtCore/QMap>
54 #include <QtCore/QSet>
55 #include <QtCore/qnamespace.h>
56 #include <QtCore/QSettings>
57 
58 #include <opencv2/opencv.hpp>
59 #include <set>
60 
61 #include <pcl/PCLPointCloud2.h>
62 
63 namespace pcl {
64  namespace visualization {
65  class PCLVisualizer;
66  }
67 }
68 
69 class QMenu;
70 class vtkProp;
71 template <typename T> class vtkSmartPointer;
72 class vtkOBBTree;
73 
74 namespace rtabmap {
75 
76 class OctoMap;
77 
79 {
80  Q_OBJECT
81 
82 public:
83  CloudViewer(QWidget * parent = 0, CloudViewerInteractorStyle* style = CloudViewerInteractorStyle::New());
84  virtual ~CloudViewer();
85 
86  void saveSettings(QSettings & settings, const QString & group = "") const;
87  void loadSettings(QSettings & settings, const QString & group = "");
88 
89  void refreshView();
90 
91  bool updateCloudPose(
92  const std::string & id,
93  const Transform & pose); //including mesh
94 
95  bool addCloud(
96  const std::string & id,
97  const pcl::PCLPointCloud2Ptr & binaryCloud,
98  const Transform & pose,
99  bool rgb,
100  bool hasNormals,
101  bool hasIntensity,
102  const QColor & color = QColor(),
103  int viewport = 1);
104 
105  bool addCloud(
106  const std::string & id,
107  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
108  const Transform & pose = Transform::getIdentity(),
109  const QColor & color = QColor());
110 
111  bool addCloud(
112  const std::string & id,
113  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
114  const Transform & pose = Transform::getIdentity(),
115  const QColor & color = QColor());
116 
117  bool addCloud(
118  const std::string & id,
119  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
120  const Transform & pose = Transform::getIdentity(),
121  const QColor & color = QColor());
122 
123  bool addCloud(
124  const std::string & id,
125  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
126  const Transform & pose = Transform::getIdentity(),
127  const QColor & color = QColor());
128 
129  bool addCloud(
130  const std::string & id,
131  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
132  const Transform & pose = Transform::getIdentity(),
133  const QColor & color = QColor());
134 
135  bool addCloud(
136  const std::string & id,
137  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
138  const Transform & pose = Transform::getIdentity(),
139  const QColor & color = QColor());
140 
141  bool addCloudMesh(
142  const std::string & id,
143  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
144  const std::vector<pcl::Vertices> & polygons,
145  const Transform & pose = Transform::getIdentity());
146 
147  bool addCloudMesh(
148  const std::string & id,
149  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
150  const std::vector<pcl::Vertices> & polygons,
151  const Transform & pose = Transform::getIdentity());
152 
153  bool addCloudMesh(
154  const std::string & id,
155  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
156  const std::vector<pcl::Vertices> & polygons,
157  const Transform & pose = Transform::getIdentity());
158 
159  bool addCloudMesh(
160  const std::string & id,
161  const pcl::PolygonMesh::Ptr & mesh,
162  const Transform & pose = Transform::getIdentity());
163 
164  // Only one texture per mesh is supported!
165  bool addCloudTextureMesh(
166  const std::string & id,
167  const pcl::TextureMesh::Ptr & textureMesh,
168  const cv::Mat & texture,
169  const Transform & pose = Transform::getIdentity());
170 
171  bool addOctomap(const OctoMap * octomap, unsigned int treeDepth = 0, bool volumeRepresentation = true);
172  void removeOctomap();
173 
174  // Only one texture per mesh is supported!
175  bool addTextureMesh (
176  const pcl::TextureMesh &mesh,
177  const cv::Mat & texture,
178  const std::string &id = "texture",
179  int viewport = 0);
180  bool addOccupancyGridMap(
181  const cv::Mat & map8U,
182  float resolution, // cell size
183  float xMin,
184  float yMin,
185  float opacity);
186  void removeOccupancyGridMap();
187 
188  void updateCameraTargetPosition(
189  const Transform & pose);
190 
191  void updateCameraFrustum(
192  const Transform & pose,
193  const StereoCameraModel & model);
194 
195  void updateCameraFrustum(
196  const Transform & pose,
197  const CameraModel & model);
198 
199  void updateCameraFrustums(
200  const Transform & pose,
201  const std::vector<CameraModel> & models);
202 
203  void updateCameraFrustums(
204  const Transform & pose,
205  const std::vector<StereoCameraModel> & models);
206 
207  void addOrUpdateCoordinate(
208  const std::string & id,
209  const Transform & transform,
210  double scale,
211  bool foreground=false);
212  bool updateCoordinatePose(
213  const std::string & id,
214  const Transform & transform);
215  void removeCoordinate(const std::string & id);
216  void removeAllCoordinates(const std::string & prefix = "");
217  const std::set<std::string> & getAddedCoordinates() const {return _coordinates;}
218 
219  void addOrUpdateLine(
220  const std::string & id,
221  const Transform & from,
222  const Transform & to,
223  const QColor & color,
224  bool arrow = false,
225  bool foreground = false);
226  void removeLine(const std::string & id);
227  void removeAllLines();
228  const std::set<std::string> & getAddedLines() const {return _lines;}
229 
230  void addOrUpdateSphere(
231  const std::string & id,
232  const Transform & pose,
233  float radius,
234  const QColor & color,
235  bool foreground = false);
236  void removeSphere(const std::string & id);
237  void removeAllSpheres();
238  const std::set<std::string> & getAddedSpheres() const {return _spheres;}
239 
240  void addOrUpdateCube(
241  const std::string & id,
242  const Transform & pose, // center of the cube
243  float width, // e.g., along x axis
244  float height, // e.g., along y axis
245  float depth, // e.g., along z axis
246  const QColor & color,
247  bool wireframe = false,
248  bool foreground = false);
249  void removeCube(const std::string & id);
250  void removeAllCubes();
251  const std::set<std::string> & getAddedCubes() const {return _cubes;}
252 
253  void addOrUpdateQuad(
254  const std::string & id,
255  const Transform & pose,
256  float width,
257  float height,
258  const QColor & color,
259  bool foreground = false);
260  void addOrUpdateQuad(
261  const std::string & id,
262  const Transform & pose,
263  float widthLeft,
264  float widthRight,
265  float heightBottom,
266  float heightTop,
267  const QColor & color,
268  bool foreground = false);
269  void removeQuad(const std::string & id);
270  void removeAllQuads();
271  const std::set<std::string> & getAddedQuads() const {return _quads;}
272 
273  void addOrUpdateFrustum(
274  const std::string & id,
275  const Transform & pose,
276  const Transform & localTransform,
277  double scale,
278  const QColor & color = QColor(),
279  float fovX=1.1,
280  float fovY=0.85);
281  bool updateFrustumPose(
282  const std::string & id,
283  const Transform & pose);
284  void removeFrustum(const std::string & id);
285  void removeAllFrustums(bool exceptCameraReference = false);
286  const QMap<std::string, Transform> & getAddedFrustums() const {return _frustums;}
287 
288  void addOrUpdateGraph(
289  const std::string & id,
290  const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
291  const QColor & color = Qt::gray);
292  void removeGraph(const std::string & id);
293  void removeAllGraphs();
294 
295  void addOrUpdateText(
296  const std::string & id,
297  const std::string & text,
298  const Transform & position,
299  double scale,
300  const QColor & color,
301  bool foreground = true);
302  void removeText(const std::string & id);
303  void removeAllTexts();
304  const std::set<std::string> & getAddedTexts() const {return _texts;}
305 
306  bool isTrajectoryShown() const;
307  unsigned int getTrajectorySize() const;
308  void setTrajectoryShown(bool shown);
309  void setTrajectorySize(unsigned int value);
310  void clearTrajectory();
311  bool isCameraAxisShown() const;
312  void setCameraAxisShown(bool shown);
313  double getCoordinateFrameScale() const;
314  void setCoordinateFrameScale(double scale);
315  bool isFrustumShown() const;
316  float getFrustumScale() const;
317  QColor getFrustumColor() const;
318  void setFrustumShown(bool shown);
319  void setFrustumScale(float value);
320  void setFrustumColor(QColor value);
321  void resetCamera();
322 
323  void removeAllClouds(); //including meshes
324  bool removeCloud(const std::string & id); //including mesh
325 
326  bool getPose(const std::string & id, Transform & pose); //including meshes
327  bool getCloudVisibility(const std::string & id);
328 
329  const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
330  const QColor & getDefaultBackgroundColor() const;
331  const QColor & getBackgroundColor() const;
332  Transform getTargetPose() const;
333  std::string getIdByActor(vtkProp * actor) const;
334  QColor getColor(const std::string & id);
335  void setColor(const std::string & id, const QColor & color);
336 
337  void setBackfaceCulling(bool enabled, bool frontfaceCulling);
338  void setPolygonPicking(bool enabled);
339  void setRenderingRate(double rate);
340  void setEDLShading(bool on);
341  void setLighting(bool on);
342  void setShading(bool on);
343  void setEdgeVisibility(bool visible);
344  void setInteractorLayer(int layer);
345 
346  bool isBackfaceCulling() const;
347  bool isFrontfaceCulling() const;
348  bool isPolygonPicking() const;
349  bool isEDLShadingOn() const;
350  bool isLightingOn() const;
351  bool isShadingOn() const;
352  bool isEdgeVisible() const;
353  double getRenderingRate() const;
354 
355  void getCameraPosition(
356  float & x, float & y, float & z,
357  float & focalX, float & focalY, float & focalZ,
358  float & upX, float & upY, float & upZ) const;
359  bool isCameraTargetLocked() const;
360  bool isCameraTargetFollow() const;
361  bool isCameraFree() const;
362  bool isCameraLockZ() const;
363  bool isCameraOrtho() const;
364  bool isGridShown() const;
365  unsigned int getGridCellCount() const;
366  float getGridCellSize() const;
367 
368  void setCameraPosition(
369  float x, float y, float z,
370  float focalX, float focalY, float focalZ,
371  float upX, float upY, float upZ);
372  void setCameraTargetLocked(bool enabled = true);
373  void setCameraTargetFollow(bool enabled = true);
374  void setCameraFree();
375  void setCameraLockZ(bool enabled = true);
376  void setCameraOrtho(bool enabled = true);
377  void setGridShown(bool shown);
378  void setNormalsShown(bool shown);
379  void setGridCellCount(unsigned int count);
380  void setGridCellSize(float size);
381  bool isNormalsShown() const;
382  int getNormalsStep() const;
383  float getNormalsScale() const;
384  void setNormalsStep(int step);
385  void setNormalsScale(float scale);
386  bool isIntensityRedColormap() const;
387  bool isIntensityRainbowColormap() const;
388  float getIntensityMax() const;
389  void setIntensityRedColormap(bool value);
390  void setIntensityRainbowColormap(bool value);
391  void setIntensityMax(float value);
392  void buildPickingLocator(bool enable);
393  const std::map<std::string, vtkSmartPointer<vtkOBBTree> > & getLocators() const {return _locators;}
394 
395 public Q_SLOTS:
396  void setDefaultBackgroundColor(const QColor & color);
397  void setBackgroundColor(const QColor & color);
398  void setCloudVisibility(const std::string & id, bool isVisible);
399  void setCloudColorIndex(const std::string & id, int index);
400  void setCloudOpacity(const std::string & id, double opacity = 1.0);
401  void setCloudPointSize(const std::string & id, int size);
402  virtual void clear();
403 
404 Q_SIGNALS:
405  void configChanged();
406 
407 protected:
408  virtual void keyReleaseEvent(QKeyEvent * event);
409  virtual void keyPressEvent(QKeyEvent * event);
410  virtual void mousePressEvent(QMouseEvent * event);
411  virtual void mouseMoveEvent(QMouseEvent * event);
412  virtual void wheelEvent(QWheelEvent * event);
413  virtual void contextMenuEvent(QContextMenuEvent * event);
414  virtual void handleAction(QAction * event);
415  QMenu * menu() {return _menu;}
416  pcl::visualization::PCLVisualizer * visualizer() {return _visualizer;}
417 
418 private:
419  void createMenu();
420  void addGrid();
421  void removeGrid();
422 
423 private:
424  pcl::visualization::PCLVisualizer * _visualizer;
425  QAction * _aLockCamera;
426  QAction * _aFollowCamera;
427  QAction * _aResetCamera;
428  QAction * _aLockViewZ;
429  QAction * _aCameraOrtho;
430  QAction * _aShowTrajectory;
432  QAction * _aClearTrajectory;
433  QAction * _aShowCameraAxis;
434  QAction * _aSetFrameScale;
435  QAction * _aShowFrustum;
436  QAction * _aSetFrustumScale;
437  QAction * _aSetFrustumColor;
438  QAction * _aShowGrid;
440  QAction * _aSetGridCellSize;
441  QAction * _aShowNormals;
442  QAction * _aSetNormalsStep;
443  QAction * _aSetNormalsScale;
449  QAction * _aSetEDLShading;
450  QAction * _aSetLighting;
451  QAction * _aSetFlatShading;
453  QAction * _aBackfaceCulling;
454  QAction * _aPolygonPicking;
455  QMenu * _menu;
456  std::set<std::string> _graphes;
457  std::set<std::string> _coordinates;
458  std::set<std::string> _texts;
459  std::set<std::string> _lines;
460  std::set<std::string> _spheres;
461  std::set<std::string> _cubes;
462  std::set<std::string> _quads;
463  QMap<std::string, Transform> _frustums;
464  pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
465  unsigned int _maxTrajectorySize;
468  unsigned int _gridCellCount;
473  std::map<std::string, vtkSmartPointer<vtkOBBTree> > _locators;
475  cv::Vec3d _lastCameraPose;
476  QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
478  std::list<std::string> _gridLines;
479  QSet<Qt::Key> _keysPressed;
484  vtkProp * _octomapActor;
487 };
488 
489 } /* namespace rtabmap */
490 #endif /* CLOUDVIEWER_H_ */
QAction * _aShowCameraAxis
Definition: CloudViewer.h:433
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
QAction * _aBackfaceCulling
Definition: CloudViewer.h:453
QAction * _aSetFrustumScale
Definition: CloudViewer.h:436
const std::set< std::string > & getAddedCubes() const
Definition: CloudViewer.h:251
std::set< std::string > _coordinates
Definition: CloudViewer.h:457
pcl::visualization::PCLVisualizer * _visualizer
Definition: CloudViewer.h:424
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
Definition: CloudViewer.h:473
QAction * _aLockCamera
Definition: CloudViewer.h:425
QAction * _aShowFrustum
Definition: CloudViewer.h:435
QAction * _aSetIntensityRainbowColormap
Definition: CloudViewer.h:445
QAction * _aSetEdgeVisibility
Definition: CloudViewer.h:452
std::list< std::string > _gridLines
Definition: CloudViewer.h:478
x
unsigned int _maxTrajectorySize
Definition: CloudViewer.h:465
const QMap< std::string, Transform > & getAddedFrustums() const
Definition: CloudViewer.h:286
std::set< std::string > _quads
Definition: CloudViewer.h:462
const std::set< std::string > & getAddedLines() const
Definition: CloudViewer.h:228
QAction * _aPolygonPicking
Definition: CloudViewer.h:454
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
cv::Vec3d _lastCameraOrientation
Definition: CloudViewer.h:474
const std::set< std::string > & getAddedCoordinates() const
Definition: CloudViewer.h:217
QVTKWidget PCLQVTKWidget
Definition: CloudViewer.h:45
std::set< std::string > _spheres
Definition: CloudViewer.h:460
QSet< Qt::Key > _keysPressed
Definition: CloudViewer.h:479
const std::set< std::string > & getAddedQuads() const
Definition: CloudViewer.h:271
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
Definition: CloudViewer.h:456
QAction * _aSetEDLShading
Definition: CloudViewer.h:449
QAction * _aSetNormalsScale
Definition: CloudViewer.h:443
std::set< std::string > _texts
Definition: CloudViewer.h:458
QAction * _aSetFrustumColor
Definition: CloudViewer.h:437
QMap< std::string, Transform > _addedClouds
Definition: CloudViewer.h:476
QAction * _aSetTrajectorySize
Definition: CloudViewer.h:431
QAction * _aSetBackgroundColor
Definition: CloudViewer.h:447
QAction * _aResetCamera
Definition: CloudViewer.h:427
const std::map< std::string, vtkSmartPointer< vtkOBBTree > > & getLocators() const
Definition: CloudViewer.h:393
QAction * _aShowTrajectory
Definition: CloudViewer.h:430
double _coordinateFrameScale
Definition: CloudViewer.h:486
pcl::visualization::PCLVisualizer * visualizer()
Definition: CloudViewer.h:416
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
Definition: CloudViewer.h:464
vtkProp * _octomapActor
Definition: CloudViewer.h:484
QAction * _aSetNormalsStep
Definition: CloudViewer.h:442
QAction * _aFollowCamera
Definition: CloudViewer.h:426
std::set< std::string > _lines
Definition: CloudViewer.h:459
QAction * _aClearTrajectory
Definition: CloudViewer.h:432
QAction * _aSetIntensityMaximum
Definition: CloudViewer.h:446
QAction * _aSetGridCellSize
Definition: CloudViewer.h:440
unsigned int _gridCellCount
Definition: CloudViewer.h:468
QAction * _aSetFrameScale
Definition: CloudViewer.h:434
std::set< std::string > _cubes
Definition: CloudViewer.h:461
QMap< std::string, Transform > _frustums
Definition: CloudViewer.h:463
model
Definition: trace.py:4
const std::set< std::string > & getAddedSpheres() const
Definition: CloudViewer.h:238
QAction * _aSetFlatShading
Definition: CloudViewer.h:451
QAction * _aSetGridCellCount
Definition: CloudViewer.h:439
QAction * _aCameraOrtho
Definition: CloudViewer.h:429
QAction * _aSetIntensityRedColormap
Definition: CloudViewer.h:444
QAction * _aShowNormals
Definition: CloudViewer.h:441
cv::Vec3d _lastCameraPose
Definition: CloudViewer.h:475
const QMap< std::string, Transform > & getAddedClouds() const
Definition: CloudViewer.h:329
QAction * _aSetRenderingRate
Definition: CloudViewer.h:448
const std::set< std::string > & getAddedTexts() const
Definition: CloudViewer.h:304
QAction * _aSetLighting
Definition: CloudViewer.h:450


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28