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 
93  bool addCloud(
94  const std::string & id,
95  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
96  const Transform & pose = Transform::getIdentity(),
97  const QColor & color = QColor());
98 
99  bool addCloud(
100  const std::string & id,
101  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
102  const Transform & pose = Transform::getIdentity(),
103  const QColor & color = QColor());
104 
105  bool addCloud(
106  const std::string & id,
107  const pcl::PointCloud<pcl::PointXYZINormal>::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::PointXYZI>::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::PointNormal>::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::PointXYZ>::Ptr & cloud,
126  const Transform & pose = Transform::getIdentity(),
127  const QColor & color = QColor());
128 
129  bool addCloudMesh(
130  const std::string & id,
131  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
132  const std::vector<pcl::Vertices> & polygons,
133  const Transform & pose = Transform::getIdentity());
134 
135  bool addCloudMesh(
136  const std::string & id,
137  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
138  const std::vector<pcl::Vertices> & polygons,
139  const Transform & pose = Transform::getIdentity());
140 
141  bool addCloudMesh(
142  const std::string & id,
143  const pcl::PointCloud<pcl::PointXYZRGBNormal>::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::PolygonMesh::Ptr & mesh,
150  const Transform & pose = Transform::getIdentity());
151 
152  // Only one texture per mesh is supported!
153  bool addCloudTextureMesh(
154  const std::string & id,
155  const pcl::TextureMesh::Ptr & textureMesh,
156  const cv::Mat & texture,
157  const Transform & pose = Transform::getIdentity());
158 
159  bool addOctomap(const OctoMap * octomap, unsigned int treeDepth = 0, bool volumeRepresentation = true);
160  void removeOctomap();
161 
162  // Only one texture per mesh is supported!
163  bool addTextureMesh (
164  const pcl::TextureMesh &mesh,
165  const cv::Mat & texture,
166  const std::string &id = "texture",
167  int viewport = 0);
168  bool addOccupancyGridMap(
169  const cv::Mat & map8U,
170  float resolution, // cell size
171  float xMin,
172  float yMin,
173  float opacity);
174  void removeOccupancyGridMap();
175 
176  void updateCameraTargetPosition(
177  const Transform & pose);
178 
179  void updateCameraFrustum(
180  const Transform & pose,
181  const StereoCameraModel & model);
182 
183  void updateCameraFrustum(
184  const Transform & pose,
185  const CameraModel & model);
186 
187  void updateCameraFrustums(
188  const Transform & pose,
189  const std::vector<CameraModel> & models);
190 
191  void addOrUpdateCoordinate(
192  const std::string & id,
193  const Transform & transform,
194  double scale,
195  bool foreground=false);
196  bool updateCoordinatePose(
197  const std::string & id,
198  const Transform & transform);
199  void removeCoordinate(const std::string & id);
200  void removeAllCoordinates();
201  const std::set<std::string> & getAddedCoordinates() const {return _coordinates;}
202 
203  void addOrUpdateLine(
204  const std::string & id,
205  const Transform & from,
206  const Transform & to,
207  const QColor & color,
208  bool arrow = false,
209  bool foreground = false);
210  void removeLine(const std::string & id);
211  void removeAllLines();
212  const std::set<std::string> & getAddedLines() const {return _lines;}
213 
214  void addOrUpdateSphere(
215  const std::string & id,
216  const Transform & pose,
217  float radius,
218  const QColor & color,
219  bool foreground = false);
220  void removeSphere(const std::string & id);
221  void removeAllSpheres();
222  const std::set<std::string> & getAddedSpheres() const {return _spheres;}
223 
224  void addOrUpdateCube(
225  const std::string & id,
226  const Transform & pose, // center of the cube
227  float width, // e.g., along x axis
228  float height, // e.g., along y axis
229  float depth, // e.g., along z axis
230  const QColor & color,
231  bool wireframe = false,
232  bool foreground = false);
233  void removeCube(const std::string & id);
234  void removeAllCubes();
235  const std::set<std::string> & getAddedCubes() const {return _cubes;}
236 
237  void addOrUpdateQuad(
238  const std::string & id,
239  const Transform & pose,
240  float width,
241  float height,
242  const QColor & color,
243  bool foreground = false);
244  void addOrUpdateQuad(
245  const std::string & id,
246  const Transform & pose,
247  float widthLeft,
248  float widthRight,
249  float heightBottom,
250  float heightTop,
251  const QColor & color,
252  bool foreground = false);
253  void removeQuad(const std::string & id);
254  void removeAllQuads();
255  const std::set<std::string> & getAddedQuads() const {return _quads;}
256 
257  void addOrUpdateFrustum(
258  const std::string & id,
259  const Transform & transform,
260  const Transform & localTransform,
261  double scale,
262  const QColor & color = QColor());
263  bool updateFrustumPose(
264  const std::string & id,
265  const Transform & pose);
266  void removeFrustum(const std::string & id);
267  void removeAllFrustums(bool exceptCameraReference = false);
268  const QMap<std::string, Transform> & getAddedFrustums() const {return _frustums;}
269 
270  void addOrUpdateGraph(
271  const std::string & id,
272  const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
273  const QColor & color = Qt::gray);
274  void removeGraph(const std::string & id);
275  void removeAllGraphs();
276 
277  void addOrUpdateText(
278  const std::string & id,
279  const std::string & text,
280  const Transform & position,
281  double scale,
282  const QColor & color,
283  bool foreground = true);
284  void removeText(const std::string & id);
285  void removeAllTexts();
286  const std::set<std::string> & getAddedTexts() const {return _texts;}
287 
288  bool isTrajectoryShown() const;
289  unsigned int getTrajectorySize() const;
290  void setTrajectoryShown(bool shown);
291  void setTrajectorySize(unsigned int value);
292  void clearTrajectory();
293  bool isFrustumShown() const;
294  float getFrustumScale() const;
295  QColor getFrustumColor() const;
296  void setFrustumShown(bool shown);
297  void setFrustumScale(float value);
298  void setFrustumColor(QColor value);
299  void resetCamera();
300 
301  void removeAllClouds(); //including meshes
302  bool removeCloud(const std::string & id); //including mesh
303 
304  bool getPose(const std::string & id, Transform & pose); //including meshes
305  bool getCloudVisibility(const std::string & id);
306 
307  const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
308  const QColor & getDefaultBackgroundColor() const;
309  const QColor & getBackgroundColor() const;
310  Transform getTargetPose() const;
311  std::string getIdByActor(vtkProp * actor) const;
312  QColor getColor(const std::string & id);
313  void setColor(const std::string & id, const QColor & color);
314 
315  void setBackfaceCulling(bool enabled, bool frontfaceCulling);
316  void setPolygonPicking(bool enabled);
317  void setRenderingRate(double rate);
318  void setLighting(bool on);
319  void setShading(bool on);
320  void setEdgeVisibility(bool visible);
321  void setInteractorLayer(int layer);
322  double getRenderingRate() const;
323 
324  void getCameraPosition(
325  float & x, float & y, float & z,
326  float & focalX, float & focalY, float & focalZ,
327  float & upX, float & upY, float & upZ) const;
328  bool isCameraTargetLocked() const;
329  bool isCameraTargetFollow() const;
330  bool isCameraFree() const;
331  bool isCameraLockZ() const;
332  bool isCameraOrtho() const;
333  bool isGridShown() const;
334  unsigned int getGridCellCount() const;
335  float getGridCellSize() const;
336 
337  void setCameraPosition(
338  float x, float y, float z,
339  float focalX, float focalY, float focalZ,
340  float upX, float upY, float upZ);
341  void setCameraTargetLocked(bool enabled = true);
342  void setCameraTargetFollow(bool enabled = true);
343  void setCameraFree();
344  void setCameraLockZ(bool enabled = true);
345  void setCameraOrtho(bool enabled = true);
346  void setGridShown(bool shown);
347  void setNormalsShown(bool shown);
348  void setGridCellCount(unsigned int count);
349  void setGridCellSize(float size);
350  bool isNormalsShown() const;
351  int getNormalsStep() const;
352  float getNormalsScale() const;
353  void setNormalsStep(int step);
354  void setNormalsScale(float scale);
355  void buildPickingLocator(bool enable);
356  const std::map<std::string, vtkSmartPointer<vtkOBBTree> > & getLocators() const {return _locators;}
357 
358 public Q_SLOTS:
359  void setDefaultBackgroundColor(const QColor & color);
360  void setBackgroundColor(const QColor & color);
361  void setCloudVisibility(const std::string & id, bool isVisible);
362  void setCloudColorIndex(const std::string & id, int index);
363  void setCloudOpacity(const std::string & id, double opacity = 1.0);
364  void setCloudPointSize(const std::string & id, int size);
365  virtual void clear();
366 
367 Q_SIGNALS:
368  void configChanged();
369 
370 protected:
371  virtual void keyReleaseEvent(QKeyEvent * event);
372  virtual void keyPressEvent(QKeyEvent * event);
373  virtual void mousePressEvent(QMouseEvent * event);
374  virtual void mouseMoveEvent(QMouseEvent * event);
375  virtual void wheelEvent(QWheelEvent * event);
376  virtual void contextMenuEvent(QContextMenuEvent * event);
377  virtual void handleAction(QAction * event);
378  QMenu * menu() {return _menu;}
379  pcl::visualization::PCLVisualizer * visualizer() {return _visualizer;}
380 
381 private:
382  void createMenu();
383  void addGrid();
384  void removeGrid();
385 
386 private:
387  pcl::visualization::PCLVisualizer * _visualizer;
388  QAction * _aLockCamera;
389  QAction * _aFollowCamera;
390  QAction * _aResetCamera;
391  QAction * _aLockViewZ;
392  QAction * _aCameraOrtho;
393  QAction * _aShowTrajectory;
395  QAction * _aClearTrajectory;
396  QAction * _aShowFrustum;
397  QAction * _aSetFrustumScale;
398  QAction * _aSetFrustumColor;
399  QAction * _aShowGrid;
401  QAction * _aSetGridCellSize;
402  QAction * _aShowNormals;
403  QAction * _aSetNormalsStep;
404  QAction * _aSetNormalsScale;
407  QAction * _aSetLighting;
408  QAction * _aSetFlatShading;
410  QAction * _aBackfaceCulling;
411  QAction * _aPolygonPicking;
412  QMenu * _menu;
413  std::set<std::string> _graphes;
414  std::set<std::string> _coordinates;
415  std::set<std::string> _texts;
416  std::set<std::string> _lines;
417  std::set<std::string> _spheres;
418  std::set<std::string> _cubes;
419  std::set<std::string> _quads;
420  QMap<std::string, Transform> _frustums;
421  pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
422  unsigned int _maxTrajectorySize;
425  unsigned int _gridCellCount;
430  std::map<std::string, vtkSmartPointer<vtkOBBTree> > _locators;
432  cv::Vec3d _lastCameraPose;
433  QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
435  std::list<std::string> _gridLines;
436  QSet<Qt::Key> _keysPressed;
441  vtkProp * _octomapActor;
442 };
443 
444 } /* namespace rtabmap */
445 #endif /* CLOUDVIEWER_H_ */
#define RTABMAPGUI_EXP
Definition: RtabmapGuiExp.h:38
const std::set< std::string > & getAddedQuads() const
Definition: CloudViewer.h:255
QAction * _aBackfaceCulling
Definition: CloudViewer.h:410
QAction * _aSetFrustumScale
Definition: CloudViewer.h:397
std::set< std::string > _coordinates
Definition: CloudViewer.h:414
pcl::visualization::PCLVisualizer * _visualizer
Definition: CloudViewer.h:387
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
Definition: CloudViewer.h:430
QAction * _aLockCamera
Definition: CloudViewer.h:388
const std::set< std::string > & getAddedTexts() const
Definition: CloudViewer.h:286
QAction * _aShowFrustum
Definition: CloudViewer.h:396
QAction * _aSetEdgeVisibility
Definition: CloudViewer.h:409
std::list< std::string > _gridLines
Definition: CloudViewer.h:435
unsigned int _maxTrajectorySize
Definition: CloudViewer.h:422
Definition: CameraRGBD.h:59
std::set< std::string > _quads
Definition: CloudViewer.h:419
QAction * _aPolygonPicking
Definition: CloudViewer.h:411
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:431
std::set< std::string > _spheres
Definition: CloudViewer.h:417
QSet< Qt::Key > _keysPressed
Definition: CloudViewer.h:436
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
Definition: CloudViewer.h:413
QAction * _aSetNormalsScale
Definition: CloudViewer.h:404
std::set< std::string > _texts
Definition: CloudViewer.h:415
QAction * _aSetFrustumColor
Definition: CloudViewer.h:398
QMap< std::string, Transform > _addedClouds
Definition: CloudViewer.h:433
QAction * _aSetTrajectorySize
Definition: CloudViewer.h:394
QAction * _aSetBackgroundColor
Definition: CloudViewer.h:405
QAction * _aResetCamera
Definition: CloudViewer.h:390
const std::set< std::string > & getAddedCoordinates() const
Definition: CloudViewer.h:201
QAction * _aShowTrajectory
Definition: CloudViewer.h:393
const QMap< std::string, Transform > & getAddedClouds() const
Definition: CloudViewer.h:307
pcl::visualization::PCLVisualizer * visualizer()
Definition: CloudViewer.h:379
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
Definition: CloudViewer.h:421
vtkProp * _octomapActor
Definition: CloudViewer.h:441
QAction * _aSetNormalsStep
Definition: CloudViewer.h:403
QAction * _aFollowCamera
Definition: CloudViewer.h:389
std::set< std::string > _lines
Definition: CloudViewer.h:416
QAction * _aClearTrajectory
Definition: CloudViewer.h:395
QAction * _aSetGridCellSize
Definition: CloudViewer.h:401
unsigned int _gridCellCount
Definition: CloudViewer.h:425
const QMap< std::string, Transform > & getAddedFrustums() const
Definition: CloudViewer.h:268
const std::set< std::string > & getAddedLines() const
Definition: CloudViewer.h:212
std::set< std::string > _cubes
Definition: CloudViewer.h:418
QMap< std::string, Transform > _frustums
Definition: CloudViewer.h:420
const std::set< std::string > & getAddedSpheres() const
Definition: CloudViewer.h:222
QAction * _aSetFlatShading
Definition: CloudViewer.h:408
QAction * _aSetGridCellCount
Definition: CloudViewer.h:400
const std::set< std::string > & getAddedCubes() const
Definition: CloudViewer.h:235
const std::map< std::string, vtkSmartPointer< vtkOBBTree > > & getLocators() const
Definition: CloudViewer.h:356
QAction * _aCameraOrtho
Definition: CloudViewer.h:392
QAction * _aShowNormals
Definition: CloudViewer.h:402
cv::Vec3d _lastCameraPose
Definition: CloudViewer.h:432
QAction * _aSetRenderingRate
Definition: CloudViewer.h:406
QAction * _aSetLighting
Definition: CloudViewer.h:407


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30