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 CLOUDVIEWER_H_
00029 #define 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 
00036 #include <QVTKWidget.h>
00037 #include <pcl/pcl_base.h>
00038 #include <pcl/point_types.h>
00039 #include <pcl/point_cloud.h>
00040 #include <pcl/PolygonMesh.h>
00041 #include <pcl/TextureMesh.h>
00042 
00043 #include <QtCore/QMap>
00044 #include <QtCore/QSet>
00045 #include <QtCore/qnamespace.h>
00046 #include <QtCore/QSettings>
00047 
00048 #include <opencv2/opencv.hpp>
00049 #include <set>
00050 
00051 #include <pcl/visualization/mouse_event.h>
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 
00063 namespace rtabmap {
00064 
00065 class OctoMap;
00066 
00067 class RTABMAPGUI_EXP CloudViewer : public QVTKWidget
00068 {
00069         Q_OBJECT
00070 
00071 public:
00072         CloudViewer(QWidget * parent = 0);
00073         virtual ~CloudViewer();
00074 
00075         void saveSettings(QSettings & settings, const QString & group = "") const;
00076         void loadSettings(QSettings & settings, const QString & group = "");
00077 
00078         bool updateCloudPose(
00079                 const std::string & id,
00080                 const Transform & pose); //including mesh
00081 
00082         bool addCloud(
00083                         const std::string & id,
00084                         const pcl::PCLPointCloud2Ptr & binaryCloud,
00085                         const Transform & pose,
00086                         bool rgb,
00087                         bool haveNormals,
00088                         const QColor & color = QColor());
00089 
00090         bool addCloud(
00091                         const std::string & id,
00092                         const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00093                         const Transform & pose = Transform::getIdentity(),
00094                         const QColor & color = QColor());
00095 
00096         bool addCloud(
00097                         const std::string & id,
00098                         const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00099                         const Transform & pose = Transform::getIdentity(),
00100                         const QColor & color = QColor());
00101 
00102         bool addCloud(
00103                         const std::string & id,
00104                         const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00105                         const Transform & pose = Transform::getIdentity(),
00106                         const QColor & color = QColor());
00107 
00108         bool addCloud(
00109                         const std::string & id,
00110                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00111                         const Transform & pose = Transform::getIdentity(),
00112                         const QColor & color = QColor());
00113 
00114         bool addCloudMesh(
00115                         const std::string & id,
00116                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00117                         const std::vector<pcl::Vertices> & polygons,
00118                         const Transform & pose = Transform::getIdentity());
00119 
00120         bool addCloudMesh(
00121                         const std::string & id,
00122                         const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00123                         const std::vector<pcl::Vertices> & polygons,
00124                         const Transform & pose = Transform::getIdentity());
00125 
00126         bool addCloudMesh(
00127                         const std::string & id,
00128                         const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00129                         const std::vector<pcl::Vertices> & polygons,
00130                         const Transform & pose = Transform::getIdentity());
00131 
00132         bool addCloudMesh(
00133                         const std::string & id,
00134                         const pcl::PolygonMesh::Ptr & mesh,
00135                         const Transform & pose = Transform::getIdentity());
00136 
00137         bool addCloudTextureMesh(
00138                         const std::string & id,
00139                         const pcl::TextureMesh::Ptr & textureMesh,
00140                         const Transform & pose = Transform::getIdentity());
00141 
00142         bool addOctomap(const OctoMap * octomap, unsigned int treeDepth = 0, bool showEdges = true, bool lightingOn = false);
00143         void removeOctomap();
00144 
00145         bool addOccupancyGridMap(
00146                         const cv::Mat & map8U,
00147                         float resolution, // cell size
00148                         float xMin,
00149                         float yMin,
00150                         float opacity);
00151         void removeOccupancyGridMap();
00152 
00153         void updateCameraTargetPosition(
00154                 const Transform & pose);
00155 
00156         void updateCameraFrustum(
00157                         const Transform & pose,
00158                         const StereoCameraModel & model);
00159 
00160         void updateCameraFrustum(
00161                         const Transform & pose,
00162                         const CameraModel & model);
00163 
00164         void updateCameraFrustums(
00165                         const Transform & pose,
00166                         const std::vector<CameraModel> & models);
00167 
00168         void addOrUpdateCoordinate(
00169                         const std::string & id,
00170                         const Transform & transform,
00171                         double scale);
00172         bool updateCoordinatePose(
00173                         const std::string & id,
00174                         const Transform & transform);
00175         void removeCoordinate(const std::string & id);
00176         void removeAllCoordinates();
00177 
00178         void addOrUpdateLine(
00179                                 const std::string & id,
00180                                 const Transform & from,
00181                                 const Transform & to,
00182                                 const QColor & color,
00183                                 bool arrow = false);
00184         void removeLine(const std::string & id);
00185         void removeAllLines();
00186 
00187         void addOrUpdateFrustum(
00188                         const std::string & id,
00189                         const Transform & transform,
00190                         double scale,
00191                         const QColor & color = QColor());
00192         bool updateFrustumPose(
00193                         const std::string & id,
00194                         const Transform & pose);
00195         void removeFrustum(const std::string & id);
00196         void removeAllFrustums();
00197 
00198         void addOrUpdateGraph(
00199                         const std::string & id,
00200                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
00201                         const QColor & color = Qt::gray);
00202         void removeGraph(const std::string & id);
00203         void removeAllGraphs();
00204 
00205         void addOrUpdateText(
00206                         const std::string & id,
00207                         const std::string & text,
00208                         const Transform & position,
00209                         double scale,
00210                         const QColor & color);
00211         void removeText(const std::string & id);
00212         void removeAllTexts();
00213 
00214         bool isTrajectoryShown() const;
00215         unsigned int getTrajectorySize() const;
00216         void setTrajectoryShown(bool shown);
00217         void setTrajectorySize(unsigned int value);
00218         void clearTrajectory();
00219         bool isFrustumShown() const;
00220         float getFrustumScale() const;
00221         QColor getFrustumColor() const;
00222         void setFrustumShown(bool shown);
00223         void setFrustumScale(float value);
00224         void setFrustumColor(QColor value);
00225         void resetCamera();
00226 
00227         void removeAllClouds(); //including meshes
00228         bool removeCloud(const std::string & id); //including mesh
00229 
00230         bool getPose(const std::string & id, Transform & pose); //including meshes
00231         bool getCloudVisibility(const std::string & id);
00232 
00233         const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
00234         const QColor & getDefaultBackgroundColor() const;
00235         const QColor & getBackgroundColor() const;
00236         Transform getTargetPose() const;
00237 
00238         void setBackfaceCulling(bool enabled, bool frontfaceCulling);
00239         void setRenderingRate(double rate);
00240         double getRenderingRate() const;
00241 
00242         void getCameraPosition(
00243                         float & x, float & y, float & z,
00244                         float & focalX, float & focalY, float & focalZ,
00245                         float & upX, float & upY, float & upZ) const;
00246         bool isCameraTargetLocked() const;
00247         bool isCameraTargetFollow() const;
00248         bool isCameraFree() const;
00249         bool isCameraLockZ() const;
00250         bool isGridShown() const;
00251         unsigned int getGridCellCount() const;
00252         float getGridCellSize() const;
00253 
00254         void setCameraPosition(
00255                         float x, float y, float z,
00256                         float focalX, float focalY, float focalZ,
00257                         float upX, float upY, float upZ);
00258         void setCameraTargetLocked(bool enabled = true);
00259         void setCameraTargetFollow(bool enabled = true);
00260         void setCameraFree();
00261         void setCameraLockZ(bool enabled = true);
00262         void setGridShown(bool shown);
00263         void setGridCellCount(unsigned int count);
00264         void setGridCellSize(float size);
00265 
00266         void setWorkingDirectory(const QString & path) {_workingDirectory = path;}
00267 
00268 public slots:
00269         void setDefaultBackgroundColor(const QColor & color);
00270         void setBackgroundColor(const QColor & color);
00271         void setCloudVisibility(const std::string & id, bool isVisible);
00272         void setCloudOpacity(const std::string & id, double opacity = 1.0);
00273         void setCloudPointSize(const std::string & id, int size);
00274         virtual void clear();
00275 
00276 signals:
00277         void configChanged();
00278 
00279 protected:
00280         virtual void keyReleaseEvent(QKeyEvent * event);
00281         virtual void keyPressEvent(QKeyEvent * event);
00282         virtual void mousePressEvent(QMouseEvent * event);
00283         virtual void mouseMoveEvent(QMouseEvent * event);
00284         virtual void wheelEvent(QWheelEvent * event);
00285         virtual void contextMenuEvent(QContextMenuEvent * event);
00286         virtual void handleAction(QAction * event);
00287         QMenu * menu() {return _menu;}
00288 
00289 private:
00290         void createMenu();
00291         void addGrid();
00292         void removeGrid();
00293 
00294 private:
00295     pcl::visualization::PCLVisualizer * _visualizer;
00296     QAction * _aLockCamera;
00297     QAction * _aFollowCamera;
00298     QAction * _aResetCamera;
00299     QAction * _aLockViewZ;
00300     QAction * _aShowTrajectory;
00301     QAction * _aSetTrajectorySize;
00302     QAction * _aClearTrajectory;
00303     QAction * _aShowFrustum;
00304     QAction * _aSetFrustumScale;
00305     QAction * _aSetFrustumColor;
00306     QAction * _aShowGrid;
00307     QAction * _aSetGridCellCount;
00308     QAction * _aSetGridCellSize;
00309     QAction * _aSetBackgroundColor;
00310     QAction * _aSetRenderingRate;
00311     QMenu * _menu;
00312     std::set<std::string> _graphes;
00313     std::set<std::string> _coordinates;
00314     std::set<std::string> _texts;
00315     std::set<std::string> _lines;
00316     std::set<std::string> _frustums;
00317     pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
00318     unsigned int _maxTrajectorySize;
00319     float _frustumScale;
00320     QColor _frustumColor;
00321     unsigned int _gridCellCount;
00322     float _gridCellSize;
00323     cv::Vec3d _lastCameraOrientation;
00324     cv::Vec3d _lastCameraPose;
00325     QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
00326     Transform _lastPose;
00327     std::list<std::string> _gridLines;
00328     QSet<Qt::Key> _keysPressed;
00329     QString _workingDirectory;
00330     QColor _defaultBgColor;
00331     QColor _currentBgColor;
00332     bool _backfaceCulling;
00333     bool _frontfaceCulling;
00334     double _renderingRate;
00335     vtkProp * _octomapActor;
00336 };
00337 
00338 } /* namespace rtabmap */
00339 #endif /* CLOUDVIEWER_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:15