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 #include <QVTKWidget.h>
38 #include <pcl/pcl_base.h>
39 #include <pcl/point_types.h>
40 #include <pcl/point_cloud.h>
41 #include <pcl/PolygonMesh.h>
42 #include <pcl/TextureMesh.h>
43 
44 #include <QtCore/QMap>
45 #include <QtCore/QSet>
46 #include <QtCore/qnamespace.h>
47 #include <QtCore/QSettings>
48 
49 #include <opencv2/opencv.hpp>
50 #include <set>
51 
52 #include <pcl/PCLPointCloud2.h>
53 
54 namespace pcl {
55  namespace visualization {
56  class PCLVisualizer;
57  }
58 }
59 
60 class QMenu;
61 class vtkProp;
62 template <typename T> class vtkSmartPointer;
63 class vtkOBBTree;
64 
65 namespace rtabmap {
66 
67 class OctoMap;
68 
69 class RTABMAPGUI_EXP CloudViewer : public QVTKWidget
70 {
71  Q_OBJECT
72 
73 public:
74  CloudViewer(QWidget * parent = 0, CloudViewerInteractorStyle* style = CloudViewerInteractorStyle::New());
75  virtual ~CloudViewer();
76 
77  void saveSettings(QSettings & settings, const QString & group = "") const;
78  void loadSettings(QSettings & settings, const QString & group = "");
79 
80  bool updateCloudPose(
81  const std::string & id,
82  const Transform & pose); //including mesh
83 
84  bool addCloud(
85  const std::string & id,
86  const pcl::PCLPointCloud2Ptr & binaryCloud,
87  const Transform & pose,
88  bool rgb,
89  bool hasNormals,
90  bool hasIntensity,
91  const QColor & color = QColor(),
92  int viewport = 1);
93 
94  bool addCloud(
95  const std::string & id,
96  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
97  const Transform & pose = Transform::getIdentity(),
98  const QColor & color = QColor());
99 
100  bool addCloud(
101  const std::string & id,
102  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
103  const Transform & pose = Transform::getIdentity(),
104  const QColor & color = QColor());
105 
106  bool addCloud(
107  const std::string & id,
108  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
109  const Transform & pose = Transform::getIdentity(),
110  const QColor & color = QColor());
111 
112  bool addCloud(
113  const std::string & id,
114  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
115  const Transform & pose = Transform::getIdentity(),
116  const QColor & color = QColor());
117 
118  bool addCloud(
119  const std::string & id,
120  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
121  const Transform & pose = Transform::getIdentity(),
122  const QColor & color = QColor());
123 
124  bool addCloud(
125  const std::string & id,
126  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
127  const Transform & pose = Transform::getIdentity(),
128  const QColor & color = QColor());
129 
130  bool addCloudMesh(
131  const std::string & id,
132  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
133  const std::vector<pcl::Vertices> & polygons,
134  const Transform & pose = Transform::getIdentity());
135 
136  bool addCloudMesh(
137  const std::string & id,
138  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
139  const std::vector<pcl::Vertices> & polygons,
140  const Transform & pose = Transform::getIdentity());
141 
142  bool addCloudMesh(
143  const std::string & id,
144  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
145  const std::vector<pcl::Vertices> & polygons,
146  const Transform & pose = Transform::getIdentity());
147 
148  bool addCloudMesh(
149  const std::string & id,
150  const pcl::PolygonMesh::Ptr & mesh,
151  const Transform & pose = Transform::getIdentity());
152 
153  // Only one texture per mesh is supported!
154  bool addCloudTextureMesh(
155  const std::string & id,
156  const pcl::TextureMesh::Ptr & textureMesh,
157  const cv::Mat & texture,
158  const Transform & pose = Transform::getIdentity());
159 
160  bool addOctomap(const OctoMap * octomap, unsigned int treeDepth = 0, bool volumeRepresentation = true);
161  void removeOctomap();
162 
163  // Only one texture per mesh is supported!
164  bool addTextureMesh (
165  const pcl::TextureMesh &mesh,
166  const cv::Mat & texture,
167  const std::string &id = "texture",
168  int viewport = 0);
169  bool addOccupancyGridMap(
170  const cv::Mat & map8U,
171  float resolution, // cell size
172  float xMin,
173  float yMin,
174  float opacity);
175  void removeOccupancyGridMap();
176 
177  void updateCameraTargetPosition(
178  const Transform & pose);
179 
180  void updateCameraFrustum(
181  const Transform & pose,
182  const StereoCameraModel & model);
183 
184  void updateCameraFrustum(
185  const Transform & pose,
186  const CameraModel & model);
187 
188  void updateCameraFrustums(
189  const Transform & pose,
190  const std::vector<CameraModel> & models);
191 
192  void addOrUpdateCoordinate(
193  const std::string & id,
194  const Transform & transform,
195  double scale,
196  bool foreground=false);
197  bool updateCoordinatePose(
198  const std::string & id,
199  const Transform & transform);
200  void removeCoordinate(const std::string & id);
201  void removeAllCoordinates(const std::string & prefix = "");
202  const std::set<std::string> & getAddedCoordinates() const {return _coordinates;}
203 
204  void addOrUpdateLine(
205  const std::string & id,
206  const Transform & from,
207  const Transform & to,
208  const QColor & color,
209  bool arrow = false,
210  bool foreground = false);
211  void removeLine(const std::string & id);
212  void removeAllLines();
213  const std::set<std::string> & getAddedLines() const {return _lines;}
214 
215  void addOrUpdateSphere(
216  const std::string & id,
217  const Transform & pose,
218  float radius,
219  const QColor & color,
220  bool foreground = false);
221  void removeSphere(const std::string & id);
222  void removeAllSpheres();
223  const std::set<std::string> & getAddedSpheres() const {return _spheres;}
224 
225  void addOrUpdateCube(
226  const std::string & id,
227  const Transform & pose, // center of the cube
228  float width, // e.g., along x axis
229  float height, // e.g., along y axis
230  float depth, // e.g., along z axis
231  const QColor & color,
232  bool wireframe = false,
233  bool foreground = false);
234  void removeCube(const std::string & id);
235  void removeAllCubes();
236  const std::set<std::string> & getAddedCubes() const {return _cubes;}
237 
238  void addOrUpdateQuad(
239  const std::string & id,
240  const Transform & pose,
241  float width,
242  float height,
243  const QColor & color,
244  bool foreground = false);
245  void addOrUpdateQuad(
246  const std::string & id,
247  const Transform & pose,
248  float widthLeft,
249  float widthRight,
250  float heightBottom,
251  float heightTop,
252  const QColor & color,
253  bool foreground = false);
254  void removeQuad(const std::string & id);
255  void removeAllQuads();
256  const std::set<std::string> & getAddedQuads() const {return _quads;}
257 
258  void addOrUpdateFrustum(
259  const std::string & id,
260  const Transform & pose,
261  const Transform & localTransform,
262  double scale,
263  const QColor & color = QColor(),
264  float fovX=1.1,
265  float fovY=0.85);
266  bool updateFrustumPose(
267  const std::string & id,
268  const Transform & pose);
269  void removeFrustum(const std::string & id);
270  void removeAllFrustums(bool exceptCameraReference = false);
271  const QMap<std::string, Transform> & getAddedFrustums() const {return _frustums;}
272 
273  void addOrUpdateGraph(
274  const std::string & id,
275  const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
276  const QColor & color = Qt::gray);
277  void removeGraph(const std::string & id);
278  void removeAllGraphs();
279 
280  void addOrUpdateText(
281  const std::string & id,
282  const std::string & text,
283  const Transform & position,
284  double scale,
285  const QColor & color,
286  bool foreground = true);
287  void removeText(const std::string & id);
288  void removeAllTexts();
289  const std::set<std::string> & getAddedTexts() const {return _texts;}
290 
291  bool isTrajectoryShown() const;
292  unsigned int getTrajectorySize() const;
293  void setTrajectoryShown(bool shown);
294  void setTrajectorySize(unsigned int value);
295  void clearTrajectory();
296  bool isCameraAxisShown() const;
297  void setCameraAxisShown(bool shown);
298  double getCoordinateFrameScale() const;
299  void setCoordinateFrameScale(double scale);
300  bool isFrustumShown() const;
301  float getFrustumScale() const;
302  QColor getFrustumColor() const;
303  void setFrustumShown(bool shown);
304  void setFrustumScale(float value);
305  void setFrustumColor(QColor value);
306  void resetCamera();
307 
308  void removeAllClouds(); //including meshes
309  bool removeCloud(const std::string & id); //including mesh
310 
311  bool getPose(const std::string & id, Transform & pose); //including meshes
312  bool getCloudVisibility(const std::string & id);
313 
314  const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
315  const QColor & getDefaultBackgroundColor() const;
316  const QColor & getBackgroundColor() const;
317  Transform getTargetPose() const;
318  std::string getIdByActor(vtkProp * actor) const;
319  QColor getColor(const std::string & id);
320  void setColor(const std::string & id, const QColor & color);
321 
322  void setBackfaceCulling(bool enabled, bool frontfaceCulling);
323  void setPolygonPicking(bool enabled);
324  void setRenderingRate(double rate);
325  void setEDLShading(bool on);
326  void setLighting(bool on);
327  void setShading(bool on);
328  void setEdgeVisibility(bool visible);
329  void setInteractorLayer(int layer);
330 
331  bool isBackfaceCulling() const;
332  bool isFrontfaceCulling() const;
333  bool isPolygonPicking() const;
334  bool isEDLShadingOn() const;
335  bool isLightingOn() const;
336  bool isShadingOn() const;
337  bool isEdgeVisible() const;
338  double getRenderingRate() const;
339 
340  void getCameraPosition(
341  float & x, float & y, float & z,
342  float & focalX, float & focalY, float & focalZ,
343  float & upX, float & upY, float & upZ) const;
344  bool isCameraTargetLocked() const;
345  bool isCameraTargetFollow() const;
346  bool isCameraFree() const;
347  bool isCameraLockZ() const;
348  bool isCameraOrtho() const;
349  bool isGridShown() const;
350  unsigned int getGridCellCount() const;
351  float getGridCellSize() const;
352 
353  void setCameraPosition(
354  float x, float y, float z,
355  float focalX, float focalY, float focalZ,
356  float upX, float upY, float upZ);
357  void setCameraTargetLocked(bool enabled = true);
358  void setCameraTargetFollow(bool enabled = true);
359  void setCameraFree();
360  void setCameraLockZ(bool enabled = true);
361  void setCameraOrtho(bool enabled = true);
362  void setGridShown(bool shown);
363  void setNormalsShown(bool shown);
364  void setGridCellCount(unsigned int count);
365  void setGridCellSize(float size);
366  bool isNormalsShown() const;
367  int getNormalsStep() const;
368  float getNormalsScale() const;
369  void setNormalsStep(int step);
370  void setNormalsScale(float scale);
371  bool isIntensityRedColormap() const;
372  bool isIntensityRainbowColormap() const;
373  float getIntensityMax() const;
374  void setIntensityRedColormap(bool value);
375  void setIntensityRainbowColormap(bool value);
376  void setIntensityMax(float value);
377  void buildPickingLocator(bool enable);
378  const std::map<std::string, vtkSmartPointer<vtkOBBTree> > & getLocators() const {return _locators;}
379 
380 public Q_SLOTS:
381  void setDefaultBackgroundColor(const QColor & color);
382  void setBackgroundColor(const QColor & color);
383  void setCloudVisibility(const std::string & id, bool isVisible);
384  void setCloudColorIndex(const std::string & id, int index);
385  void setCloudOpacity(const std::string & id, double opacity = 1.0);
386  void setCloudPointSize(const std::string & id, int size);
387  virtual void clear();
388 
389 Q_SIGNALS:
390  void configChanged();
391 
392 protected:
393  virtual void keyReleaseEvent(QKeyEvent * event);
394  virtual void keyPressEvent(QKeyEvent * event);
395  virtual void mousePressEvent(QMouseEvent * event);
396  virtual void mouseMoveEvent(QMouseEvent * event);
397  virtual void wheelEvent(QWheelEvent * event);
398  virtual void contextMenuEvent(QContextMenuEvent * event);
399  virtual void handleAction(QAction * event);
400  QMenu * menu() {return _menu;}
401  pcl::visualization::PCLVisualizer * visualizer() {return _visualizer;}
402 
403 private:
404  void createMenu();
405  void addGrid();
406  void removeGrid();
407 
408 private:
409  pcl::visualization::PCLVisualizer * _visualizer;
410  QAction * _aLockCamera;
411  QAction * _aFollowCamera;
412  QAction * _aResetCamera;
413  QAction * _aLockViewZ;
414  QAction * _aCameraOrtho;
415  QAction * _aShowTrajectory;
417  QAction * _aClearTrajectory;
418  QAction * _aShowCameraAxis;
419  QAction * _aSetFrameScale;
420  QAction * _aShowFrustum;
421  QAction * _aSetFrustumScale;
422  QAction * _aSetFrustumColor;
423  QAction * _aShowGrid;
425  QAction * _aSetGridCellSize;
426  QAction * _aShowNormals;
427  QAction * _aSetNormalsStep;
428  QAction * _aSetNormalsScale;
434  QAction * _aSetEDLShading;
435  QAction * _aSetLighting;
436  QAction * _aSetFlatShading;
438  QAction * _aBackfaceCulling;
439  QAction * _aPolygonPicking;
440  QMenu * _menu;
441  std::set<std::string> _graphes;
442  std::set<std::string> _coordinates;
443  std::set<std::string> _texts;
444  std::set<std::string> _lines;
445  std::set<std::string> _spheres;
446  std::set<std::string> _cubes;
447  std::set<std::string> _quads;
448  QMap<std::string, Transform> _frustums;
449  pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
450  unsigned int _maxTrajectorySize;
453  unsigned int _gridCellCount;
458  std::map<std::string, vtkSmartPointer<vtkOBBTree> > _locators;
460  cv::Vec3d _lastCameraPose;
461  QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
463  std::list<std::string> _gridLines;
464  QSet<Qt::Key> _keysPressed;
469  vtkProp * _octomapActor;
472 };
473 
474 } /* namespace rtabmap */
475 #endif /* CLOUDVIEWER_H_ */
QAction * _aShowCameraAxis
Definition: CloudViewer.h:418
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
const std::set< std::string > & getAddedQuads() const
Definition: CloudViewer.h:256
QAction * _aBackfaceCulling
Definition: CloudViewer.h:438
QAction * _aSetFrustumScale
Definition: CloudViewer.h:421
std::set< std::string > _coordinates
Definition: CloudViewer.h:442
pcl::visualization::PCLVisualizer * _visualizer
Definition: CloudViewer.h:409
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
Definition: CloudViewer.h:458
QAction * _aLockCamera
Definition: CloudViewer.h:410
const std::set< std::string > & getAddedTexts() const
Definition: CloudViewer.h:289
QAction * _aShowFrustum
Definition: CloudViewer.h:420
QAction * _aSetIntensityRainbowColormap
Definition: CloudViewer.h:430
QAction * _aSetEdgeVisibility
Definition: CloudViewer.h:437
std::list< std::string > _gridLines
Definition: CloudViewer.h:463
unsigned int _maxTrajectorySize
Definition: CloudViewer.h:450
std::set< std::string > _quads
Definition: CloudViewer.h:447
QAction * _aPolygonPicking
Definition: CloudViewer.h:439
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:459
std::set< std::string > _spheres
Definition: CloudViewer.h:445
QSet< Qt::Key > _keysPressed
Definition: CloudViewer.h:464
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
Definition: CloudViewer.h:441
QAction * _aSetEDLShading
Definition: CloudViewer.h:434
QAction * _aSetNormalsScale
Definition: CloudViewer.h:428
std::set< std::string > _texts
Definition: CloudViewer.h:443
QAction * _aSetFrustumColor
Definition: CloudViewer.h:422
QMap< std::string, Transform > _addedClouds
Definition: CloudViewer.h:461
QAction * _aSetTrajectorySize
Definition: CloudViewer.h:416
QAction * _aSetBackgroundColor
Definition: CloudViewer.h:432
QAction * _aResetCamera
Definition: CloudViewer.h:412
const std::set< std::string > & getAddedCoordinates() const
Definition: CloudViewer.h:202
QAction * _aShowTrajectory
Definition: CloudViewer.h:415
double _coordinateFrameScale
Definition: CloudViewer.h:471
const QMap< std::string, Transform > & getAddedClouds() const
Definition: CloudViewer.h:314
pcl::visualization::PCLVisualizer * visualizer()
Definition: CloudViewer.h:401
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
Definition: CloudViewer.h:449
vtkProp * _octomapActor
Definition: CloudViewer.h:469
QAction * _aSetNormalsStep
Definition: CloudViewer.h:427
QAction * _aFollowCamera
Definition: CloudViewer.h:411
std::set< std::string > _lines
Definition: CloudViewer.h:444
QAction * _aClearTrajectory
Definition: CloudViewer.h:417
QAction * _aSetIntensityMaximum
Definition: CloudViewer.h:431
QAction * _aSetGridCellSize
Definition: CloudViewer.h:425
unsigned int _gridCellCount
Definition: CloudViewer.h:453
const QMap< std::string, Transform > & getAddedFrustums() const
Definition: CloudViewer.h:271
const std::set< std::string > & getAddedLines() const
Definition: CloudViewer.h:213
QAction * _aSetFrameScale
Definition: CloudViewer.h:419
std::set< std::string > _cubes
Definition: CloudViewer.h:446
QMap< std::string, Transform > _frustums
Definition: CloudViewer.h:448
const std::set< std::string > & getAddedSpheres() const
Definition: CloudViewer.h:223
QAction * _aSetFlatShading
Definition: CloudViewer.h:436
QAction * _aSetGridCellCount
Definition: CloudViewer.h:424
const std::set< std::string > & getAddedCubes() const
Definition: CloudViewer.h:236
const std::map< std::string, vtkSmartPointer< vtkOBBTree > > & getLocators() const
Definition: CloudViewer.h:378
QAction * _aCameraOrtho
Definition: CloudViewer.h:414
QAction * _aSetIntensityRedColormap
Definition: CloudViewer.h:429
QAction * _aShowNormals
Definition: CloudViewer.h:426
cv::Vec3d _lastCameraPose
Definition: CloudViewer.h:460
QAction * _aSetRenderingRate
Definition: CloudViewer.h:433
QAction * _aSetLighting
Definition: CloudViewer.h:435


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58