CloudViewer.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef RTABMAP_CLOUDVIEWER_H_
00029 #define RTABMAP_CLOUDVIEWER_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include "rtabmap/core/Transform.h"
00034 #include "rtabmap/core/StereoCameraModel.h"
00035 #include "rtabmap/gui/CloudViewerInteractorStyle.h"
00036 
00037 #include <QVTKWidget.h>
00038 #include <pcl/pcl_base.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/point_cloud.h>
00041 #include <pcl/PolygonMesh.h>
00042 #include <pcl/TextureMesh.h>
00043 
00044 #include <QtCore/QMap>
00045 #include <QtCore/QSet>
00046 #include <QtCore/qnamespace.h>
00047 #include <QtCore/QSettings>
00048 
00049 #include <opencv2/opencv.hpp>
00050 #include <set>
00051 
00052 #include <pcl/PCLPointCloud2.h>
00053 
00054 namespace pcl {
00055         namespace visualization {
00056                 class PCLVisualizer;
00057         }
00058 }
00059 
00060 class QMenu;
00061 class vtkProp;
00062 template <typename T> class vtkSmartPointer;
00063 class vtkOBBTree;
00064 
00065 namespace rtabmap {
00066 
00067 class OctoMap;
00068 
00069 class RTABMAPGUI_EXP CloudViewer : public QVTKWidget
00070 {
00071         Q_OBJECT
00072 
00073 public:
00074         CloudViewer(QWidget * parent = 0, CloudViewerInteractorStyle* style = CloudViewerInteractorStyle::New());
00075         virtual ~CloudViewer();
00076 
00077         void saveSettings(QSettings & settings, const QString & group = "") const;
00078         void loadSettings(QSettings & settings, const QString & group = "");
00079 
00080         bool updateCloudPose(
00081                 const std::string & id,
00082                 const Transform & pose); //including mesh
00083 
00084         bool addCloud(
00085                         const std::string & id,
00086                         const pcl::PCLPointCloud2Ptr & binaryCloud,
00087                         const Transform & pose,
00088                         bool rgb,
00089                         bool hasNormals,
00090                         bool hasIntensity,
00091                         const QColor & color = QColor());
00092 
00093         bool addCloud(
00094                         const std::string & id,
00095                         const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00096                         const Transform & pose = Transform::getIdentity(),
00097                         const QColor & color = QColor());
00098 
00099         bool addCloud(
00100                         const std::string & id,
00101                         const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00102                         const Transform & pose = Transform::getIdentity(),
00103                         const QColor & color = QColor());
00104 
00105         bool addCloud(
00106                                 const std::string & id,
00107                                 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00108                                 const Transform & pose = Transform::getIdentity(),
00109                                 const QColor & color = QColor());
00110 
00111         bool addCloud(
00112                         const std::string & id,
00113                         const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00114                         const Transform & pose = Transform::getIdentity(),
00115                         const QColor & color = QColor());
00116 
00117         bool addCloud(
00118                         const std::string & id,
00119                         const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00120                         const Transform & pose = Transform::getIdentity(),
00121                         const QColor & color = QColor());
00122 
00123         bool addCloud(
00124                         const std::string & id,
00125                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00126                         const Transform & pose = Transform::getIdentity(),
00127                         const QColor & color = QColor());
00128 
00129         bool addCloudMesh(
00130                         const std::string & id,
00131                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00132                         const std::vector<pcl::Vertices> & polygons,
00133                         const Transform & pose = Transform::getIdentity());
00134 
00135         bool addCloudMesh(
00136                         const std::string & id,
00137                         const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00138                         const std::vector<pcl::Vertices> & polygons,
00139                         const Transform & pose = Transform::getIdentity());
00140 
00141         bool addCloudMesh(
00142                         const std::string & id,
00143                         const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00144                         const std::vector<pcl::Vertices> & polygons,
00145                         const Transform & pose = Transform::getIdentity());
00146 
00147         bool addCloudMesh(
00148                         const std::string & id,
00149                         const pcl::PolygonMesh::Ptr & mesh,
00150                         const Transform & pose = Transform::getIdentity());
00151 
00152         // Only one texture per mesh is supported!
00153         bool addCloudTextureMesh(
00154                         const std::string & id,
00155                         const pcl::TextureMesh::Ptr & textureMesh,
00156                         const cv::Mat & texture,
00157                         const Transform & pose = Transform::getIdentity());
00158 
00159         bool addOctomap(const OctoMap * octomap, unsigned int treeDepth = 0, bool volumeRepresentation = true);
00160         void removeOctomap();
00161 
00162         // Only one texture per mesh is supported!
00163         bool addTextureMesh (
00164                    const pcl::TextureMesh &mesh,
00165                    const cv::Mat & texture, 
00166                    const std::string &id = "texture",
00167                    int viewport = 0);
00168         bool addOccupancyGridMap(
00169                         const cv::Mat & map8U,
00170                         float resolution, // cell size
00171                         float xMin,
00172                         float yMin,
00173                         float opacity);
00174         void removeOccupancyGridMap();
00175 
00176         void updateCameraTargetPosition(
00177                 const Transform & pose);
00178 
00179         void updateCameraFrustum(
00180                         const Transform & pose,
00181                         const StereoCameraModel & model);
00182 
00183         void updateCameraFrustum(
00184                         const Transform & pose,
00185                         const CameraModel & model);
00186 
00187         void updateCameraFrustums(
00188                         const Transform & pose,
00189                         const std::vector<CameraModel> & models);
00190 
00191         void addOrUpdateCoordinate(
00192                         const std::string & id,
00193                         const Transform & transform,
00194                         double scale,
00195                         bool foreground=false);
00196         bool updateCoordinatePose(
00197                         const std::string & id,
00198                         const Transform & transform);
00199         void removeCoordinate(const std::string & id);
00200         void removeAllCoordinates();
00201         const std::set<std::string> & getAddedCoordinates() const {return _coordinates;}
00202 
00203         void addOrUpdateLine(
00204                                 const std::string & id,
00205                                 const Transform & from,
00206                                 const Transform & to,
00207                                 const QColor & color,
00208                                 bool arrow = false,
00209                                 bool foreground = false);
00210         void removeLine(const std::string & id);
00211         void removeAllLines();
00212         const std::set<std::string> & getAddedLines() const {return _lines;}
00213 
00214         void addOrUpdateSphere(
00215                                 const std::string & id,
00216                                 const Transform & pose,
00217                                 float radius,
00218                                 const QColor & color,
00219                                 bool foreground = false);
00220         void removeSphere(const std::string & id);
00221         void removeAllSpheres();
00222         const std::set<std::string> & getAddedSpheres() const {return _spheres;}
00223 
00224         void addOrUpdateCube(
00225                                 const std::string & id,
00226                                 const Transform & pose, // center of the cube
00227                                 float width,  // e.g., along x axis
00228                                 float height, // e.g., along y axis
00229                                 float depth,  // e.g., along z axis
00230                                 const QColor & color,
00231                                 bool wireframe = false,
00232                                 bool foreground = false);
00233         void removeCube(const std::string & id);
00234         void removeAllCubes();
00235         const std::set<std::string> & getAddedCubes() const {return _cubes;}
00236 
00237         void addOrUpdateQuad(
00238                         const std::string & id,
00239                         const Transform & pose,
00240                         float width,
00241                         float height,
00242                         const QColor & color,
00243                         bool foreground = false);
00244         void addOrUpdateQuad(
00245                         const std::string & id,
00246                         const Transform & pose,
00247                         float widthLeft,
00248                         float widthRight,
00249                         float heightBottom,
00250                         float heightTop,
00251                         const QColor & color,
00252                         bool foreground = false);
00253         void removeQuad(const std::string & id);
00254         void removeAllQuads();
00255         const std::set<std::string> & getAddedQuads() const {return _quads;}
00256 
00257         void addOrUpdateFrustum(
00258                         const std::string & id,
00259                         const Transform & transform,
00260                         const Transform & localTransform,
00261                         double scale,
00262                         const QColor & color = QColor());
00263         bool updateFrustumPose(
00264                         const std::string & id,
00265                         const Transform & pose);
00266         void removeFrustum(const std::string & id);
00267         void removeAllFrustums(bool exceptCameraReference = false);
00268         const QMap<std::string, Transform> & getAddedFrustums() const {return _frustums;}
00269 
00270         void addOrUpdateGraph(
00271                         const std::string & id,
00272                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
00273                         const QColor & color = Qt::gray);
00274         void removeGraph(const std::string & id);
00275         void removeAllGraphs();
00276 
00277         void addOrUpdateText(
00278                         const std::string & id,
00279                         const std::string & text,
00280                         const Transform & position,
00281                         double scale,
00282                         const QColor & color,
00283                         bool foreground = true);
00284         void removeText(const std::string & id);
00285         void removeAllTexts();
00286         const std::set<std::string> & getAddedTexts() const {return _texts;}
00287 
00288         bool isTrajectoryShown() const;
00289         unsigned int getTrajectorySize() const;
00290         void setTrajectoryShown(bool shown);
00291         void setTrajectorySize(unsigned int value);
00292         void clearTrajectory();
00293         bool isFrustumShown() const;
00294         float getFrustumScale() const;
00295         QColor getFrustumColor() const;
00296         void setFrustumShown(bool shown);
00297         void setFrustumScale(float value);
00298         void setFrustumColor(QColor value);
00299         void resetCamera();
00300 
00301         void removeAllClouds(); //including meshes
00302         bool removeCloud(const std::string & id); //including mesh
00303 
00304         bool getPose(const std::string & id, Transform & pose); //including meshes
00305         bool getCloudVisibility(const std::string & id);
00306 
00307         const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
00308         const QColor & getDefaultBackgroundColor() const;
00309         const QColor & getBackgroundColor() const;
00310         Transform getTargetPose() const;
00311         std::string getIdByActor(vtkProp * actor) const;
00312         QColor getColor(const std::string & id);
00313         void setColor(const std::string & id, const QColor & color);
00314 
00315         void setBackfaceCulling(bool enabled, bool frontfaceCulling);
00316         void setPolygonPicking(bool enabled);
00317         void setRenderingRate(double rate);
00318         void setLighting(bool on);
00319         void setShading(bool on);
00320         void setEdgeVisibility(bool visible);
00321         void setInteractorLayer(int layer);
00322         double getRenderingRate() const;
00323 
00324         void getCameraPosition(
00325                         float & x, float & y, float & z,
00326                         float & focalX, float & focalY, float & focalZ,
00327                         float & upX, float & upY, float & upZ) const;
00328         bool isCameraTargetLocked() const;
00329         bool isCameraTargetFollow() const;
00330         bool isCameraFree() const;
00331         bool isCameraLockZ() const;
00332         bool isCameraOrtho() const;
00333         bool isGridShown() const;
00334         unsigned int getGridCellCount() const;
00335         float getGridCellSize() const;
00336 
00337         void setCameraPosition(
00338                         float x, float y, float z,
00339                         float focalX, float focalY, float focalZ,
00340                         float upX, float upY, float upZ);
00341         void setCameraTargetLocked(bool enabled = true);
00342         void setCameraTargetFollow(bool enabled = true);
00343         void setCameraFree();
00344         void setCameraLockZ(bool enabled = true);
00345         void setCameraOrtho(bool enabled = true);
00346         void setGridShown(bool shown);
00347         void setNormalsShown(bool shown);
00348         void setGridCellCount(unsigned int count);
00349         void setGridCellSize(float size);
00350         bool isNormalsShown() const;
00351         int getNormalsStep() const;
00352         float getNormalsScale() const;
00353         void setNormalsStep(int step);
00354         void setNormalsScale(float scale);
00355         void buildPickingLocator(bool enable);
00356         const std::map<std::string, vtkSmartPointer<vtkOBBTree> > & getLocators() const {return _locators;}
00357 
00358 public Q_SLOTS:
00359         void setDefaultBackgroundColor(const QColor & color);
00360         void setBackgroundColor(const QColor & color);
00361         void setCloudVisibility(const std::string & id, bool isVisible);
00362         void setCloudColorIndex(const std::string & id, int index);
00363         void setCloudOpacity(const std::string & id, double opacity = 1.0);
00364         void setCloudPointSize(const std::string & id, int size);
00365         virtual void clear();
00366 
00367 Q_SIGNALS:
00368         void configChanged();
00369 
00370 protected:
00371         virtual void keyReleaseEvent(QKeyEvent * event);
00372         virtual void keyPressEvent(QKeyEvent * event);
00373         virtual void mousePressEvent(QMouseEvent * event);
00374         virtual void mouseMoveEvent(QMouseEvent * event);
00375         virtual void wheelEvent(QWheelEvent * event);
00376         virtual void contextMenuEvent(QContextMenuEvent * event);
00377         virtual void handleAction(QAction * event);
00378         QMenu * menu() {return _menu;}
00379         pcl::visualization::PCLVisualizer * visualizer() {return _visualizer;}
00380 
00381 private:
00382         void createMenu();
00383         void addGrid();
00384         void removeGrid();
00385 
00386 private:
00387     pcl::visualization::PCLVisualizer * _visualizer;
00388     QAction * _aLockCamera;
00389     QAction * _aFollowCamera;
00390     QAction * _aResetCamera;
00391     QAction * _aLockViewZ;
00392     QAction * _aCameraOrtho;
00393     QAction * _aShowTrajectory;
00394     QAction * _aSetTrajectorySize;
00395     QAction * _aClearTrajectory;
00396     QAction * _aShowFrustum;
00397     QAction * _aSetFrustumScale;
00398     QAction * _aSetFrustumColor;
00399     QAction * _aShowGrid;
00400     QAction * _aSetGridCellCount;
00401     QAction * _aSetGridCellSize;
00402     QAction * _aShowNormals;
00403         QAction * _aSetNormalsStep;
00404         QAction * _aSetNormalsScale;
00405     QAction * _aSetBackgroundColor;
00406     QAction * _aSetRenderingRate;
00407     QAction * _aSetLighting;
00408     QAction * _aSetFlatShading;
00409     QAction * _aSetEdgeVisibility;
00410     QAction * _aBackfaceCulling;
00411     QAction * _aPolygonPicking;
00412     QMenu * _menu;
00413     std::set<std::string> _graphes;
00414     std::set<std::string> _coordinates;
00415     std::set<std::string> _texts;
00416     std::set<std::string> _lines;
00417     std::set<std::string> _spheres;
00418     std::set<std::string> _cubes;
00419     std::set<std::string> _quads;
00420     QMap<std::string, Transform> _frustums;
00421     pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
00422     unsigned int _maxTrajectorySize;
00423     float _frustumScale;
00424     QColor _frustumColor;
00425     unsigned int _gridCellCount;
00426     float _gridCellSize;
00427     int _normalsStep;
00428     float _normalsScale;
00429     bool _buildLocator;
00430     std::map<std::string, vtkSmartPointer<vtkOBBTree> > _locators;
00431     cv::Vec3d _lastCameraOrientation;
00432     cv::Vec3d _lastCameraPose;
00433     QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
00434     Transform _lastPose;
00435     std::list<std::string> _gridLines;
00436     QSet<Qt::Key> _keysPressed;
00437     QColor _defaultBgColor;
00438     QColor _currentBgColor;
00439     bool _frontfaceCulling;
00440     double _renderingRate;
00441     vtkProp * _octomapActor;
00442 };
00443 
00444 } /* namespace rtabmap */
00445 #endif /* CLOUDVIEWER_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19