28 #ifndef RTABMAP_CLOUDVIEWER_H_ 29 #define RTABMAP_CLOUDVIEWER_H_ 37 #if VTK_MAJOR_VERSION > 8 41 #include <QVTKOpenGLNativeWidget.h> 44 #include <QVTKWidget.h> 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> 53 #include <QtCore/QMap> 54 #include <QtCore/QSet> 55 #include <QtCore/qnamespace.h> 56 #include <QtCore/QSettings> 58 #include <opencv2/opencv.hpp> 61 #include <pcl/PCLPointCloud2.h> 64 namespace visualization {
86 void saveSettings(QSettings & settings,
const QString & group =
"")
const;
87 void loadSettings(QSettings & settings,
const QString & group =
"");
92 const std::string &
id,
96 const std::string &
id,
97 const pcl::PCLPointCloud2Ptr & binaryCloud,
102 const QColor & color = QColor(),
106 const std::string &
id,
107 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
108 const Transform & pose = Transform::getIdentity(),
109 const QColor & color = QColor());
112 const std::string &
id,
113 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
114 const Transform & pose = Transform::getIdentity(),
115 const QColor & color = QColor());
118 const std::string &
id,
119 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
120 const Transform & pose = Transform::getIdentity(),
121 const QColor & color = QColor());
124 const std::string &
id,
125 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
126 const Transform & pose = Transform::getIdentity(),
127 const QColor & color = QColor());
130 const std::string &
id,
131 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
132 const Transform & pose = Transform::getIdentity(),
133 const QColor & color = QColor());
136 const std::string &
id,
137 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
138 const Transform & pose = Transform::getIdentity(),
139 const QColor & color = QColor());
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());
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());
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());
160 const std::string &
id,
161 const pcl::PolygonMesh::Ptr & mesh,
162 const Transform & pose = Transform::getIdentity());
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());
171 bool addOctomap(
const OctoMap *
octomap,
unsigned int treeDepth = 0,
bool volumeRepresentation =
true);
172 void removeOctomap();
175 bool addTextureMesh (
176 const pcl::TextureMesh &mesh,
177 const cv::Mat & texture,
178 const std::string &
id =
"texture",
180 bool addOccupancyGridMap(
181 const cv::Mat & map8U,
186 void removeOccupancyGridMap();
188 void updateCameraTargetPosition(
191 void updateCameraFrustum(
195 void updateCameraFrustum(
199 void updateCameraFrustums(
201 const std::vector<CameraModel> & models);
203 void updateCameraFrustums(
205 const std::vector<StereoCameraModel> & models);
207 void addOrUpdateCoordinate(
208 const std::string &
id,
211 bool foreground=
false);
212 bool updateCoordinatePose(
213 const std::string &
id,
215 void removeCoordinate(
const std::string &
id);
216 void removeAllCoordinates(
const std::string & prefix =
"");
219 void addOrUpdateLine(
220 const std::string &
id,
223 const QColor & color,
225 bool foreground =
false);
226 void removeLine(
const std::string &
id);
227 void removeAllLines();
230 void addOrUpdateSphere(
231 const std::string &
id,
234 const QColor & color,
235 bool foreground =
false);
236 void removeSphere(
const std::string &
id);
237 void removeAllSpheres();
240 void addOrUpdateCube(
241 const std::string &
id,
246 const QColor & color,
247 bool wireframe =
false,
248 bool foreground =
false);
249 void removeCube(
const std::string &
id);
250 void removeAllCubes();
253 void addOrUpdateQuad(
254 const std::string &
id,
258 const QColor & color,
259 bool foreground =
false);
260 void addOrUpdateQuad(
261 const std::string &
id,
267 const QColor & color,
268 bool foreground =
false);
269 void removeQuad(
const std::string &
id);
270 void removeAllQuads();
273 void addOrUpdateFrustum(
274 const std::string &
id,
278 const QColor & color = QColor(),
281 bool updateFrustumPose(
282 const std::string &
id,
284 void removeFrustum(
const std::string &
id);
285 void removeAllFrustums(
bool exceptCameraReference =
false);
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();
295 void addOrUpdateText(
296 const std::string &
id,
297 const std::string & text,
300 const QColor & color,
301 bool foreground =
true);
302 void removeText(
const std::string &
id);
303 void removeAllTexts();
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);
323 void removeAllClouds();
324 bool removeCloud(
const std::string &
id);
326 bool getPose(
const std::string &
id,
Transform & pose);
327 bool getCloudVisibility(
const std::string &
id);
329 const QMap<std::string, Transform> &
getAddedClouds()
const {
return _addedClouds;}
330 const QColor & getDefaultBackgroundColor()
const;
331 const QColor & getBackgroundColor()
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);
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);
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;
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;
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;}
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();
405 void configChanged();
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);
416 pcl::visualization::PCLVisualizer *
visualizer() {
return _visualizer;}
473 std::map<std::string, vtkSmartPointer<vtkOBBTree> >
_locators;
QAction * _aShowCameraAxis
QAction * _aBackfaceCulling
QAction * _aSetFrustumScale
const std::set< std::string > & getAddedCubes() const
std::set< std::string > _coordinates
pcl::visualization::PCLVisualizer * _visualizer
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
QAction * _aSetIntensityRainbowColormap
QAction * _aSetEdgeVisibility
std::list< std::string > _gridLines
unsigned int _maxTrajectorySize
const QMap< std::string, Transform > & getAddedFrustums() const
std::set< std::string > _quads
const std::set< std::string > & getAddedLines() const
QAction * _aPolygonPicking
cv::Vec3d _lastCameraOrientation
const std::set< std::string > & getAddedCoordinates() const
std::set< std::string > _spheres
QSet< Qt::Key > _keysPressed
const std::set< std::string > & getAddedQuads() const
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::set< std::string > _graphes
QAction * _aSetEDLShading
QAction * _aSetNormalsScale
std::set< std::string > _texts
QAction * _aSetFrustumColor
QMap< std::string, Transform > _addedClouds
QAction * _aSetTrajectorySize
QAction * _aSetBackgroundColor
const std::map< std::string, vtkSmartPointer< vtkOBBTree > > & getLocators() const
QAction * _aShowTrajectory
double _coordinateFrameScale
pcl::visualization::PCLVisualizer * visualizer()
pcl::PointCloud< pcl::PointXYZ >::Ptr _trajectory
QAction * _aSetNormalsStep
std::set< std::string > _lines
QAction * _aClearTrajectory
QAction * _aSetIntensityMaximum
QAction * _aSetGridCellSize
unsigned int _gridCellCount
QAction * _aSetFrameScale
std::set< std::string > _cubes
QMap< std::string, Transform > _frustums
const std::set< std::string > & getAddedSpheres() const
QAction * _aSetFlatShading
QAction * _aSetGridCellCount
QAction * _aSetIntensityRedColormap
cv::Vec3d _lastCameraPose
const QMap< std::string, Transform > & getAddedClouds() const
QAction * _aSetRenderingRate
const std::set< std::string > & getAddedTexts() const