CloudViewer.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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 <QVTKWidget.h>
00034 #include <pcl/pcl_base.h>
00035 #include <pcl/point_types.h>
00036 #include <pcl/point_cloud.h>
00037 #include <pcl/PolygonMesh.h>
00038 #include "rtabmap/core/Transform.h"
00039 #include <QtCore/QMap>
00040 #include <QtCore/QSet>
00041 #include <QtCore/qnamespace.h>
00042 #include <QtCore/QSettings>
00043 
00044 #include <opencv2/opencv.hpp>
00045 
00046 #include <pcl/visualization/mouse_event.h>
00047 #include <pcl/PCLPointCloud2.h>
00048 
00049 namespace pcl {
00050         namespace visualization {
00051                 class PCLVisualizer;
00052         }
00053 }
00054 
00055 class QMenu;
00056 
00057 namespace rtabmap {
00058 
00059 class RTABMAPGUI_EXP CloudViewer : public QVTKWidget
00060 {
00061         Q_OBJECT
00062 
00063 public:
00064         CloudViewer(QWidget * parent = 0);
00065         virtual ~CloudViewer();
00066 
00067         void saveSettings(QSettings & settings, const QString & group = "") const;
00068         void loadSettings(QSettings & settings, const QString & group = "");
00069 
00070         bool updateCloudPose(
00071                 const std::string & id,
00072                 const Transform & pose); //including mesh
00073 
00074         bool updateCloud(
00075                 const std::string & id,
00076                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00077                 const Transform & pose = Transform::getIdentity(),
00078                 const QColor & color = QColor());
00079 
00080         bool updateCloud(
00081                 const std::string & id,
00082                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00083                 const Transform & pose = Transform::getIdentity(),
00084                 const QColor & color = QColor());
00085 
00086         bool addOrUpdateCloud(
00087                 const std::string & id,
00088                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00089                 const Transform & pose = Transform::getIdentity(),
00090                 const QColor & color = QColor());
00091 
00092         bool addOrUpdateCloud(
00093                         const std::string & id,
00094                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00095                         const Transform & pose = Transform::getIdentity(),
00096                         const QColor & color = QColor());
00097 
00098         bool addCloud(
00099                         const std::string & id,
00100                         const pcl::PCLPointCloud2Ptr & binaryCloud,
00101                         const Transform & pose,
00102                         bool rgb,
00103                         const QColor & color = QColor());
00104 
00105         bool addCloud(
00106                 const std::string & id,
00107                 const pcl::PointCloud<pcl::PointXYZRGB>::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::PointXYZ>::Ptr & cloud,
00114                 const Transform & pose = Transform::getIdentity(),
00115                 const QColor & color = QColor());
00116 
00117         bool addCloudMesh(
00118                 const std::string & id,
00119                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00120                 const std::vector<pcl::Vertices> & polygons,
00121                 const Transform & pose = Transform::getIdentity());
00122 
00123         bool addCloudMesh(
00124                 const std::string & id,
00125                 const pcl::PolygonMesh::Ptr & mesh,
00126                 const Transform & pose = Transform::getIdentity());
00127 
00128         bool addOccupancyGridMap(
00129                         const cv::Mat & map8U,
00130                         float resolution, // cell size
00131                         float xMin,
00132                         float yMin,
00133                         float opacity);
00134         void removeOccupancyGridMap();
00135 
00136         void updateCameraTargetPosition(
00137                 const Transform & pose);
00138 
00139         void addOrUpdateGraph(
00140                         const std::string & id,
00141                         const pcl::PointCloud<pcl::PointXYZ>::Ptr & graph,
00142                         const QColor & color = Qt::gray);
00143         void removeGraph(const std::string & id);
00144         void removeAllGraphs();
00145 
00146         bool isTrajectoryShown() const;
00147         unsigned int getTrajectorySize() const;
00148         void setTrajectoryShown(bool shown);
00149         void setTrajectorySize(unsigned int value);
00150         void clearTrajectory();
00151 
00152         void removeAllClouds(); //including meshes
00153         bool removeCloud(const std::string & id); //including mesh
00154 
00155         bool getPose(const std::string & id, Transform & pose); //including meshes
00156         bool getCloudVisibility(const std::string & id);
00157 
00158         const QMap<std::string, Transform> & getAddedClouds() const {return _addedClouds;} //including meshes
00159         const QColor & getDefaultBackgroundColor() const;
00160         const QColor & getBackgroundColor() const;
00161         Transform getTargetPose() const;
00162         void getCameraPosition(
00163                         float & x, float & y, float & z,
00164                         float & focalX, float & focalY, float & focalZ,
00165                         float & upX, float & upY, float & upZ) const;
00166         bool isCameraTargetLocked() const;
00167         bool isCameraTargetFollow() const;
00168         bool isCameraFree() const;
00169         bool isCameraLockZ() const;
00170         bool isGridShown() const;
00171         unsigned int getGridCellCount() const;
00172         float getGridCellSize() const;
00173 
00174         void setCameraPosition(
00175                         float x, float y, float z,
00176                         float focalX, float focalY, float focalZ,
00177                         float upX, float upY, float upZ);
00178         void setCameraTargetLocked(bool enabled = true);
00179         void setCameraTargetFollow(bool enabled = true);
00180         void setCameraFree();
00181         void setCameraLockZ(bool enabled = true);
00182         void setGridShown(bool shown);
00183         void setGridCellCount(unsigned int count);
00184         void setGridCellSize(float size);
00185         void setWorkingDirectory(const QString & path) {_workingDirectory = path;}
00186 
00187 public slots:
00188         void setDefaultBackgroundColor(const QColor & color);
00189         void setBackgroundColor(const QColor & color);
00190         void setCloudVisibility(const std::string & id, bool isVisible);
00191         void setCloudOpacity(const std::string & id, double opacity = 1.0);
00192         void setCloudPointSize(const std::string & id, int size);
00193         virtual void clear() {removeAllClouds(); clearTrajectory();}
00194 
00195 signals:
00196         void configChanged();
00197 
00198 protected:
00199         virtual void keyReleaseEvent(QKeyEvent * event);
00200         virtual void keyPressEvent(QKeyEvent * event);
00201         virtual void mousePressEvent(QMouseEvent * event);
00202         virtual void mouseMoveEvent(QMouseEvent * event);
00203         virtual void contextMenuEvent(QContextMenuEvent * event);
00204         virtual void handleAction(QAction * event);
00205         QMenu * menu() {return _menu;}
00206 
00207 private:
00208         void createMenu();
00209         void mouseEventOccurred (const pcl::visualization::MouseEvent &event, void* viewer_void);
00210         void addGrid();
00211         void removeGrid();
00212 
00213 private:
00214     pcl::visualization::PCLVisualizer * _visualizer;
00215     QAction * _aLockCamera;
00216     QAction * _aFollowCamera;
00217     QAction * _aResetCamera;
00218     QAction * _aLockViewZ;
00219     QAction * _aShowTrajectory;
00220     QAction * _aSetTrajectorySize;
00221     QAction * _aClearTrajectory;
00222     QAction * _aShowGrid;
00223     QAction * _aSetGridCellCount;
00224     QAction * _aSetGridCellSize;
00225     QAction * _aSetBackgroundColor;
00226     QMenu * _menu;
00227     std::set<std::string> _graphes;
00228     pcl::PointCloud<pcl::PointXYZ>::Ptr _trajectory;
00229     unsigned int _maxTrajectorySize;
00230     unsigned int _gridCellCount;
00231     float _gridCellSize;
00232     QMap<std::string, Transform> _addedClouds; // include cloud, scan, meshes
00233     Transform _lastPose;
00234     std::list<std::string> _gridLines;
00235     QSet<Qt::Key> _keysPressed;
00236     QString _workingDirectory;
00237     QColor _defaultBgColor;
00238     QColor _currentBgColor;
00239 };
00240 
00241 } /* namespace rtabmap */
00242 #endif /* CLOUDVIEWER_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31