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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:08