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());
94 const std::string &
id,
95 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
96 const Transform & pose = Transform::getIdentity(),
97 const QColor & color = QColor());
100 const std::string &
id,
101 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
102 const Transform & pose = Transform::getIdentity(),
103 const QColor & color = QColor());
106 const std::string &
id,
107 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
108 const Transform & pose = Transform::getIdentity(),
109 const QColor & color = QColor());
112 const std::string &
id,
113 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
114 const Transform & pose = Transform::getIdentity(),
115 const QColor & color = QColor());
118 const std::string &
id,
119 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
120 const Transform & pose = Transform::getIdentity(),
121 const QColor & color = QColor());
124 const std::string &
id,
125 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
126 const Transform & pose = Transform::getIdentity(),
127 const QColor & color = QColor());
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());
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());
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());
148 const std::string &
id,
149 const pcl::PolygonMesh::Ptr & mesh,
150 const Transform & pose = Transform::getIdentity());
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());
159 bool addOctomap(
const OctoMap *
octomap,
unsigned int treeDepth = 0,
bool volumeRepresentation =
true);
160 void removeOctomap();
163 bool addTextureMesh (
164 const pcl::TextureMesh &mesh,
165 const cv::Mat & texture,
166 const std::string &
id =
"texture",
168 bool addOccupancyGridMap(
169 const cv::Mat & map8U,
174 void removeOccupancyGridMap();
176 void updateCameraTargetPosition(
179 void updateCameraFrustum(
183 void updateCameraFrustum(
187 void updateCameraFrustums(
189 const std::vector<CameraModel> & models);
191 void addOrUpdateCoordinate(
192 const std::string &
id,
195 bool foreground=
false);
196 bool updateCoordinatePose(
197 const std::string &
id,
199 void removeCoordinate(
const std::string &
id);
200 void removeAllCoordinates();
203 void addOrUpdateLine(
204 const std::string &
id,
207 const QColor & color,
209 bool foreground =
false);
210 void removeLine(
const std::string &
id);
211 void removeAllLines();
214 void addOrUpdateSphere(
215 const std::string &
id,
218 const QColor & color,
219 bool foreground =
false);
220 void removeSphere(
const std::string &
id);
221 void removeAllSpheres();
224 void addOrUpdateCube(
225 const std::string &
id,
230 const QColor & color,
231 bool wireframe =
false,
232 bool foreground =
false);
233 void removeCube(
const std::string &
id);
234 void removeAllCubes();
237 void addOrUpdateQuad(
238 const std::string &
id,
242 const QColor & color,
243 bool foreground =
false);
244 void addOrUpdateQuad(
245 const std::string &
id,
251 const QColor & color,
252 bool foreground =
false);
253 void removeQuad(
const std::string &
id);
254 void removeAllQuads();
257 void addOrUpdateFrustum(
258 const std::string &
id,
262 const QColor & color = QColor());
263 bool updateFrustumPose(
264 const std::string &
id,
266 void removeFrustum(
const std::string &
id);
267 void removeAllFrustums(
bool exceptCameraReference =
false);
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();
277 void addOrUpdateText(
278 const std::string &
id,
279 const std::string & text,
282 const QColor & color,
283 bool foreground =
true);
284 void removeText(
const std::string &
id);
285 void removeAllTexts();
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);
301 void removeAllClouds();
302 bool removeCloud(
const std::string &
id);
304 bool getPose(
const std::string &
id,
Transform & pose);
305 bool getCloudVisibility(
const std::string &
id);
307 const QMap<std::string, Transform> &
getAddedClouds()
const {
return _addedClouds;}
308 const QColor & getDefaultBackgroundColor()
const;
309 const QColor & getBackgroundColor()
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);
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;
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;
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;}
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();
368 void configChanged();
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);
379 pcl::visualization::PCLVisualizer *
visualizer() {
return _visualizer;}
430 std::map<std::string, vtkSmartPointer<vtkOBBTree> >
_locators;
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 * _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 * _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
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 * _aSetGridCellSize
unsigned int _gridCellCount
const QMap< std::string, Transform > & getAddedFrustums() const
const std::set< std::string > & getAddedLines() const
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
cv::Vec3d _lastCameraPose
QAction * _aSetRenderingRate