ExportCloudsDialog.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_EXPORTCLOUDSDIALOG_H_
00029 #define RTABMAP_EXPORTCLOUDSDIALOG_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include <QDialog>
00034 #include <QMap>
00035 #include <QtCore/QSettings>
00036 
00037 #include <rtabmap/core/Signature.h>
00038 #include <rtabmap/core/Parameters.h>
00039 
00040 #include <pcl/point_cloud.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/PolygonMesh.h>
00043 #include <pcl/TextureMesh.h>
00044 #include <pcl/pcl_base.h>
00045 
00046 class Ui_ExportCloudsDialog;
00047 class QAbstractButton;
00048 
00049 namespace rtabmap {
00050 class ProgressDialog;
00051 class GainCompensator;
00052 class DBDriver;
00053 
00054 class RTABMAPGUI_EXP ExportCloudsDialog : public QDialog
00055 {
00056         Q_OBJECT
00057 
00058 public:
00059         ExportCloudsDialog(QWidget *parent = 0);
00060 
00061         virtual ~ExportCloudsDialog();
00062 
00063         void saveSettings(QSettings & settings, const QString & group = "") const;
00064         void loadSettings(QSettings & settings, const QString & group = "");
00065 
00066         void setDBDriver(const DBDriver * dbDriver) {_dbDriver = dbDriver;}
00067         void forceAssembling(bool enabled);
00068         void setProgressDialogToMax();
00069         void setSaveButton();
00070         void setOkButton();
00071 
00072         void exportClouds(
00073                         const std::map<int, Transform> & poses,
00074                         const std::multimap<int, Link> & links,
00075                         const std::map<int, int> & mapIds,
00076                         const QMap<int, Signature> & cachedSignatures,
00077                         const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00078                         const std::map<int, LaserScan> & cachedScans,
00079                         const QString & workingDirectory,
00080                         const ParametersMap & parameters);
00081 
00082         void viewClouds(
00083                         const std::map<int, Transform> & poses,
00084                         const std::multimap<int, Link> & links,
00085                         const std::map<int, int> & mapIds,
00086                         const QMap<int, Signature> & cachedSignatures,
00087                         const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00088                         const std::map<int, LaserScan> & cachedScans,
00089                         const QString & workingDirectory,
00090                         const ParametersMap & parameters);
00091 
00092         bool getExportedClouds(
00093                         const std::map<int, Transform> & poses,
00094                         const std::multimap<int, Link> & links,
00095                         const std::map<int, int> & mapIds,
00096                         const QMap<int, Signature> & cachedSignatures,
00097                         const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00098                         const std::map<int, LaserScan> & cachedScans,
00099                         const QString & workingDirectory,
00100                         const ParametersMap & parameters,
00101                         std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
00102                         std::map<int, pcl::PolygonMesh::Ptr> & meshes,
00103                         std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
00104                         std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels);
00105 
00106         int getTextureSize() const;
00107         int getMaxTextures() const;
00108         bool isGainCompensation() const;
00109         double getGainBeta() const;
00110         bool isGainRGB() const;
00111         bool isBlending() const;
00112         int getBlendingDecimation() const;
00113         int getTextureBrightnessConstrastRatioLow() const;
00114         int getTextureBrightnessConstrastRatioHigh() const;
00115         bool isExposeFusion() const;
00116 
00117         static bool removeDirRecursively(const QString & dirName);
00118 
00119 Q_SIGNALS:
00120         void configChanged();
00121 
00122 public Q_SLOTS:
00123         void restoreDefaults();
00124 
00125 private Q_SLOTS:
00126         void loadSettings();
00127         void saveSettings();
00128         void updateReconstructionFlavor();
00129         void selectDistortionModel();
00130         void updateMLSGrpVisibility();
00131         void cancel();
00132 
00133 private:
00134         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > getClouds(
00135                         const std::map<int, Transform> & poses,
00136                         const QMap<int, Signature> & cachedSignatures,
00137                         const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00138                         const std::map<int, LaserScan> & cachedScans,
00139                         const ParametersMap & parameters,
00140                         bool & has2dScans) const;
00141         void saveClouds(const QString & workingDirectory, const std::map<int, Transform> & poses, const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds, bool binaryMode = true);
00142         void saveMeshes(const QString & workingDirectory, const std::map<int, Transform> & poses, const std::map<int, pcl::PolygonMesh::Ptr> & meshes, bool binaryMode = true);
00143         void saveTextureMeshes(const QString & workingDirectory, const std::map<int, Transform> & poses, std::map<int, pcl::TextureMesh::Ptr> & textureMeshes, const QMap<int, Signature> & cachedSignatures, const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels);
00144 
00145 private:
00146         Ui_ExportCloudsDialog * _ui;
00147         ProgressDialog * _progressDialog;
00148         QString _workingDirectory;
00149         bool _canceled;
00150         GainCompensator * _compensator;
00151         const DBDriver * _dbDriver;
00152 };
00153 
00154 }
00155 
00156 #endif /* EXPORTCLOUDSDIALOG_H_ */


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