28 #ifndef RTABMAP_CLOUDVIEWER_H_ 29 #define RTABMAP_CLOUDVIEWER_H_ 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> 44 #include <QtCore/QMap> 45 #include <QtCore/QSet> 46 #include <QtCore/qnamespace.h> 47 #include <QtCore/QSettings> 49 #include <opencv2/opencv.hpp> 52 #include <pcl/PCLPointCloud2.h> 55 namespace visualization {
77 void saveSettings(QSettings & settings,
const QString & group =
"")
const;
78 void loadSettings(QSettings & settings,
const QString & group =
"");
81 const std::string &
id,
85 const std::string &
id,
86 const pcl::PCLPointCloud2Ptr & binaryCloud,
91 const QColor & color = QColor(),
95 const std::string &
id,
96 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
97 const Transform & pose = Transform::getIdentity(),
98 const QColor & color = QColor());
101 const std::string &
id,
102 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
103 const Transform & pose = Transform::getIdentity(),
104 const QColor & color = QColor());
107 const std::string &
id,
108 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
109 const Transform & pose = Transform::getIdentity(),
110 const QColor & color = QColor());
113 const std::string &
id,
114 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
115 const Transform & pose = Transform::getIdentity(),
116 const QColor & color = QColor());
119 const std::string &
id,
120 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
121 const Transform & pose = Transform::getIdentity(),
122 const QColor & color = QColor());
125 const std::string &
id,
126 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
127 const Transform & pose = Transform::getIdentity(),
128 const QColor & color = QColor());
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());
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());
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());
149 const std::string &
id,
150 const pcl::PolygonMesh::Ptr & mesh,
151 const Transform & pose = Transform::getIdentity());
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());
160 bool addOctomap(
const OctoMap *
octomap,
unsigned int treeDepth = 0,
bool volumeRepresentation =
true);
161 void removeOctomap();
164 bool addTextureMesh (
165 const pcl::TextureMesh &mesh,
166 const cv::Mat & texture,
167 const std::string &
id =
"texture",
169 bool addOccupancyGridMap(
170 const cv::Mat & map8U,
175 void removeOccupancyGridMap();
177 void updateCameraTargetPosition(
180 void updateCameraFrustum(
184 void updateCameraFrustum(
188 void updateCameraFrustums(
190 const std::vector<CameraModel> & models);
192 void addOrUpdateCoordinate(
193 const std::string &
id,
196 bool foreground=
false);
197 bool updateCoordinatePose(
198 const std::string &
id,
200 void removeCoordinate(
const std::string &
id);
201 void removeAllCoordinates(
const std::string & prefix =
"");
204 void addOrUpdateLine(
205 const std::string &
id,
208 const QColor & color,
210 bool foreground =
false);
211 void removeLine(
const std::string &
id);
212 void removeAllLines();
215 void addOrUpdateSphere(
216 const std::string &
id,
219 const QColor & color,
220 bool foreground =
false);
221 void removeSphere(
const std::string &
id);
222 void removeAllSpheres();
225 void addOrUpdateCube(
226 const std::string &
id,
231 const QColor & color,
232 bool wireframe =
false,
233 bool foreground =
false);
234 void removeCube(
const std::string &
id);
235 void removeAllCubes();
238 void addOrUpdateQuad(
239 const std::string &
id,
243 const QColor & color,
244 bool foreground =
false);
245 void addOrUpdateQuad(
246 const std::string &
id,
252 const QColor & color,
253 bool foreground =
false);
254 void removeQuad(
const std::string &
id);
255 void removeAllQuads();
258 void addOrUpdateFrustum(
259 const std::string &
id,
263 const QColor & color = QColor(),
266 bool updateFrustumPose(
267 const std::string &
id,
269 void removeFrustum(
const std::string &
id);
270 void removeAllFrustums(
bool exceptCameraReference =
false);
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();
280 void addOrUpdateText(
281 const std::string &
id,
282 const std::string & text,
285 const QColor & color,
286 bool foreground =
true);
287 void removeText(
const std::string &
id);
288 void removeAllTexts();
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);
308 void removeAllClouds();
309 bool removeCloud(
const std::string &
id);
311 bool getPose(
const std::string &
id,
Transform & pose);
312 bool getCloudVisibility(
const std::string &
id);
314 const QMap<std::string, Transform> &
getAddedClouds()
const {
return _addedClouds;}
315 const QColor & getDefaultBackgroundColor()
const;
316 const QColor & getBackgroundColor()
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);
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);
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;
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;
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;}
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();
390 void configChanged();
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);
401 pcl::visualization::PCLVisualizer *
visualizer() {
return _visualizer;}
458 std::map<std::string, vtkSmartPointer<vtkOBBTree> >
_locators;
QAction * _aShowCameraAxis
const std::set< std::string > & getAddedQuads() const
QAction * _aBackfaceCulling
QAction * _aSetFrustumScale
std::set< std::string > _coordinates
pcl::visualization::PCLVisualizer * _visualizer
std::map< std::string, vtkSmartPointer< vtkOBBTree > > _locators
const std::set< std::string > & getAddedTexts() const
QAction * _aSetIntensityRainbowColormap
QAction * _aSetEdgeVisibility
std::list< std::string > _gridLines
unsigned int _maxTrajectorySize
std::set< std::string > _quads
QAction * _aPolygonPicking
cv::Vec3d _lastCameraOrientation
std::set< std::string > _spheres
QSet< Qt::Key > _keysPressed
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::set< std::string > & getAddedCoordinates() const
QAction * _aShowTrajectory
double _coordinateFrameScale
const QMap< std::string, Transform > & getAddedClouds() const
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
const QMap< std::string, Transform > & getAddedFrustums() const
const std::set< std::string > & getAddedLines() const
QAction * _aSetFrameScale
std::set< std::string > _cubes
QMap< std::string, Transform > _frustums
const std::set< std::string > & getAddedSpheres() const
QAction * _aSetFlatShading
QAction * _aSetGridCellCount
const std::set< std::string > & getAddedCubes() const
const std::map< std::string, vtkSmartPointer< vtkOBBTree > > & getLocators() const
QAction * _aSetIntensityRedColormap
cv::Vec3d _lastCameraPose
QAction * _aSetRenderingRate