MainWindow.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_MAINWINDOW_H_
00029 #define RTABMAP_MAINWINDOW_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include "rtabmap/utilite/UEventsHandler.h"
00034 #include <QMainWindow>
00035 #include <QtCore/QSet>
00036 #include "rtabmap/core/RtabmapEvent.h"
00037 #include "rtabmap/core/SensorData.h"
00038 #include "rtabmap/core/OdometryEvent.h"
00039 #include "rtabmap/core/CameraInfo.h"
00040 #include "rtabmap/gui/PreferencesDialog.h"
00041 
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/PolygonMesh.h>
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/TextureMesh.h>
00047 
00048 namespace rtabmap {
00049 class CameraThread;
00050 class OdometryThread;
00051 class IMUThread;
00052 class CloudViewer;
00053 class LoopClosureViewer;
00054 class OccupancyGrid;
00055 }
00056 
00057 class QGraphicsScene;
00058 class Ui_mainWindow;
00059 class QActionGroup;
00060 
00061 namespace rtabmap {
00062 
00063 class LikelihoodScene;
00064 class AboutDialog;
00065 class Plot;
00066 class PdfPlotCurve;
00067 class StatsToolBox;
00068 class ProgressDialog;
00069 class TwistGridWidget;
00070 class ExportCloudsDialog;
00071 class ExportBundlerDialog;
00072 class PostProcessingDialog;
00073 class DepthCalibrationDialog;
00074 class DataRecorder;
00075 class OctoMap;
00076 
00077 class RTABMAPGUI_EXP MainWindow : public QMainWindow, public UEventsHandler
00078 {
00079         Q_OBJECT
00080 
00081 public:
00082         enum State {
00083                 kIdle,
00084                 kInitializing,
00085                 kInitialized,
00086                 kApplicationClosing,
00087                 kClosing,
00088                 kStartingDetection,
00089                 kDetecting,
00090                 kPaused,
00091                 kMonitoring,
00092                 kMonitoringPaused
00093         };
00094 
00095 public:
00100         MainWindow(PreferencesDialog * prefDialog = 0, QWidget * parent = 0, bool showSplashScreen = true);
00101         virtual ~MainWindow();
00102 
00103         QString getWorkingDirectory() const;
00104         void setMonitoringState(bool pauseChecked = false); // in monitoring state, only some actions are enabled
00105         bool isSavedMaximized() const {return _savedMaximized;}
00106 
00107         bool isProcessingStatistics() const {return _processingStatistics;}
00108         bool isProcessingOdometry() const {return _processingOdometry;}
00109 
00110         bool isDatabaseUpdated() const { return _databaseUpdated; }
00111 
00112 public Q_SLOTS:
00113         virtual void processStats(const rtabmap::Statistics & stat);
00114         void updateCacheFromDatabase(const QString & path);
00115         void openDatabase(const QString & path, const rtabmap::ParametersMap & overridedParameters = rtabmap::ParametersMap());
00116         void updateParameters(const rtabmap::ParametersMap & parameters);
00117 
00118 protected:
00119         virtual void closeEvent(QCloseEvent* event);
00120         virtual bool handleEvent(UEvent* anEvent);
00121         virtual void showEvent(QShowEvent* anEvent);
00122         virtual void moveEvent(QMoveEvent* anEvent);
00123         virtual void resizeEvent(QResizeEvent* anEvent);
00124         virtual void keyPressEvent(QKeyEvent *event);
00125         virtual bool eventFilter(QObject *obj, QEvent *event);
00126 
00127 protected Q_SLOTS:
00128         virtual void changeState(MainWindow::State state);
00129         virtual void newDatabase();
00130         virtual void openDatabase();
00131         virtual bool closeDatabase();
00132         virtual void startDetection();
00133         virtual void pauseDetection();
00134         virtual void stopDetection();
00135         virtual void saveConfigGUI();
00136         virtual void downloadAllClouds();
00137         virtual void downloadPoseGraph();
00138         virtual void clearTheCache();
00139         virtual void openHelp();
00140         virtual void openPreferences();
00141         virtual void openPreferencesSource();
00142         virtual void setDefaultViews();
00143         virtual void resetOdometry();
00144         virtual void triggerNewMap();
00145         virtual void deleteMemory();
00146 
00147 protected Q_SLOTS:
00148         void beep();
00149         void cancelProgress();
00150         void configGUIModified();
00151         void editDatabase();
00152         void notifyNoMoreImages();
00153         void printLoopClosureIds();
00154         void generateGraphDOT();
00155         void exportPosesRaw();
00156         void exportPosesRGBDSLAM();
00157         void exportPosesKITTI();
00158         void exportPosesTORO();
00159         void exportPosesG2O();
00160         void exportImages();
00161         void exportOctomap();
00162         void postProcessing();
00163         void depthCalibration();
00164         void openWorkingDirectory();
00165         void updateEditMenu();
00166         void selectStream();
00167         void selectOpenni();
00168         void selectFreenect();
00169         void selectOpenniCv();
00170         void selectOpenniCvAsus();
00171         void selectOpenni2();
00172         void selectFreenect2();
00173         void selectK4W2();
00174         void selectRealSense();
00175         void selectRealSense2();
00176         void selectStereoDC1394();
00177         void selectStereoFlyCapture2();
00178         void selectStereoZed();
00179         void selectStereoUsb();
00180         void dumpTheMemory();
00181         void dumpThePrediction();
00182         void sendGoal();
00183         void sendWaypoints();
00184         void postGoal(const QString & goal);
00185         void cancelGoal();
00186         void label();
00187         void updateCacheFromDatabase();
00188         void anchorCloudsToGroundTruth();
00189         void selectScreenCaptureFormat(bool checked);
00190         void takeScreenshot();
00191         void updateElapsedTime();
00192         void processCameraInfo(const rtabmap::CameraInfo & info);
00193         void processOdometry(const rtabmap::OdometryEvent & odom, bool dataIgnored);
00194         void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
00195         void applyPrefSettings(const rtabmap::ParametersMap & parameters);
00196         void processRtabmapEventInit(int status, const QString & info);
00197         void processRtabmapEvent3DMap(const rtabmap::RtabmapEvent3DMap & event);
00198         void processRtabmapGlobalPathEvent(const rtabmap::RtabmapGlobalPathEvent & event);
00199         void processRtabmapLabelErrorEvent(int id, const QString & label);
00200         void processRtabmapGoalStatusEvent(int status);
00201         void changeImgRateSetting();
00202         void changeDetectionRateSetting();
00203         void changeTimeLimitSetting();
00204         void changeMappingMode();
00205         void setAspectRatio(int w, int h);
00206         void setAspectRatio16_9();
00207         void setAspectRatio16_10();
00208         void setAspectRatio4_3();
00209         void setAspectRatio240p();
00210         void setAspectRatio360p();
00211         void setAspectRatio480p();
00212         void setAspectRatio720p();
00213         void setAspectRatio1080p();
00214         void setAspectRatioCustom();
00215         void exportGridMap();
00216         void exportClouds();
00217         void exportBundlerFormat();
00218         void viewClouds();
00219         void dataRecorder();
00220         void dataRecorderDestroyed();
00221         void updateNodeVisibility(int, bool);
00222         void updateGraphView();
00223 
00224 Q_SIGNALS:
00225         void statsReceived(const rtabmap::Statistics &);
00226         void statsProcessed();
00227         void cameraInfoReceived(const rtabmap::CameraInfo &);
00228         void cameraInfoProcessed();
00229         void odometryReceived(const rtabmap::OdometryEvent &, bool);
00230         void odometryProcessed();
00231         void thresholdsChanged(int, int);
00232         void stateChanged(MainWindow::State);
00233         void rtabmapEventInitReceived(int status, const QString & info);
00234         void rtabmapEvent3DMapReceived(const rtabmap::RtabmapEvent3DMap & event);
00235         void rtabmapEvent3DMapProcessed();
00236         void rtabmapGlobalPathEventReceived(const rtabmap::RtabmapGlobalPathEvent & event);
00237         void rtabmapLabelErrorReceived(int id, const QString & label);
00238         void rtabmapGoalStatusEventReceived(int status);
00239         void imgRateChanged(double);
00240         void detectionRateChanged(double);
00241         void timeLimitChanged(float);
00242         void mappingModeChanged(bool);
00243         void noMoreImagesReceived();
00244         void loopClosureThrChanged(float);
00245         void twistReceived(float x, float y, float z, float roll, float pitch, float yaw, int row, int col);
00246 
00247 private:
00248         void update3DMapVisibility(bool cloudsShown, bool scansShown);
00249         void updateMapCloud(
00250                         const std::map<int, Transform> & poses,
00251                         const std::multimap<int, Link> & constraints,
00252                         const std::map<int, int> & mapIds,
00253                         const std::map<int, std::string> & labels,
00254                         const std::map<int, Transform> & groundTruths,
00255                         bool verboseProgress = false,
00256                         std::map<std::string, float> * stats = 0);
00257         std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(int nodeId,   const Transform & pose, int mapId);
00258         void createAndAddScanToMap(int nodeId, const Transform & pose, int mapId);
00259         void createAndAddFeaturesToMap(int nodeId, const Transform & pose, int mapId);
00260         Transform alignPosesToGroundTruth(const std::map<int, Transform> & poses, const std::map<int, Transform> & groundTruth);
00261         void drawKeypoints(const std::multimap<int, cv::KeyPoint> & refWords, const std::multimap<int, cv::KeyPoint> & loopWords);
00262         void setupMainLayout(bool vertical);
00263         void updateSelectSourceMenu();
00264         void applyPrefSettings(const rtabmap::ParametersMap & parameters, bool postParamEvent);
00265         void saveFigures();
00266         void loadFigures();
00267         void exportPoses(int format);
00268         QString captureScreen(bool cacheInRAM = false, bool png = true);
00269 
00270 protected:
00271         Ui_mainWindow * ui() { return _ui; }
00272         const State & state() const { return _state; }
00273 
00274         const QMap<int, Signature> & cachedSignatures() const { return _cachedSignatures;}
00275         const std::map<int, Transform> & currentPosesMap() const { return _currentPosesMap; }  // <nodeId, pose>
00276         const std::map<int, Transform> & currentGTPosesMap() const { return _currentGTPosesMap; }  // <nodeId, pose>
00277         const std::multimap<int, Link> & currentLinksMap() const { return _currentLinksMap; }  // <nodeFromId, link>
00278         const std::map<int, int> & currentMapIds() const { return _currentMapIds; }    // <nodeId, mapId>
00279         const std::map<int, std::string> & currentLabels() const { return _currentLabels; }  // <nodeId, label>
00280         const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds() const { return _cachedClouds; }
00281         const std::map<int, LaserScan> & createdScans() const { return _createdScans; }
00282         const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & createdFeatures() const { return _createdFeatures; }
00283 
00284         const rtabmap::OccupancyGrid * occupancyGrid() const { return _occupancyGrid; }
00285         const rtabmap::OctoMap * octomap() const { return _octomap; }
00286 
00287         rtabmap::ProgressDialog * progressDialog() { return _progressDialog; }
00288         rtabmap::CloudViewer * cloudViewer() const { return _cloudViewer; }
00289         rtabmap::LoopClosureViewer * loopClosureViewer() const { return _loopClosureViewer; }
00290 
00291         void setCloudViewer(rtabmap::CloudViewer * cloudViewer);
00292         void setLoopClosureViewer(rtabmap::LoopClosureViewer * loopClosureViewer);
00293 
00294         void setNewDatabasePathOutput(const QString & newDatabasePathOutput) {_newDatabasePathOutput = newDatabasePathOutput;}
00295         const QString & newDatabasePathOutput() const { return _newDatabasePathOutput; }
00296 
00297 private:
00298         Ui_mainWindow * _ui;
00299 
00300         State _state;
00301         rtabmap::CameraThread * _camera;
00302         rtabmap::OdometryThread * _odomThread;
00303         rtabmap::IMUThread * _imuThread;
00304 
00305         //Dialogs
00306         PreferencesDialog * _preferencesDialog;
00307         AboutDialog * _aboutDialog;
00308         ExportCloudsDialog * _exportCloudsDialog;
00309         ExportBundlerDialog * _exportBundlerDialog;
00310         PostProcessingDialog * _postProcessingDialog;
00311         DepthCalibrationDialog * _depthCalibrationDialog;
00312         DataRecorder * _dataRecorder;
00313 
00314         QSet<int> _lastIds;
00315         int _lastId;
00316         double _firstStamp;
00317         bool _processingStatistics;
00318         bool _processingDownloadedMap;
00319         bool _recovering;
00320         bool _odometryReceived;
00321         QString _newDatabasePath;
00322         QString _newDatabasePathOutput;
00323         QString _openedDatabasePath;
00324         bool _databaseUpdated;
00325         bool _odomImageShow;
00326         bool _odomImageDepthShow;
00327         bool _savedMaximized;
00328         QStringList _waypoints;
00329         int _waypointsIndex;
00330         std::vector<CameraModel> _rectCameraModels;
00331 
00332         QMap<int, Signature> _cachedSignatures;
00333         long _cachedMemoryUsage;
00334         std::map<int, Transform> _currentPosesMap; // <nodeId, pose>
00335         std::map<int, Transform> _currentGTPosesMap; // <nodeId, pose>
00336         std::multimap<int, Link> _currentLinksMap; // <nodeFromId, link>
00337         std::map<int, int> _currentMapIds;   // <nodeId, mapId>
00338         std::map<int, std::string> _currentLabels; // <nodeId, label>
00339         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > _cachedClouds;
00340         long _createdCloudsMemoryUsage;
00341         std::set<int> _cachedEmptyClouds;
00342         std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> > _previousCloud; // used for subtraction
00343         std::map<int, float> _cachedWordsCount;
00344         std::map<int, float> _cachedLocalizationsCount;
00345 
00346         std::map<int, LaserScan> _createdScans;
00347 
00348         rtabmap::OccupancyGrid * _occupancyGrid;
00349         rtabmap::OctoMap * _octomap;
00350 
00351         std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> _createdFeatures;
00352 
00353         Transform _odometryCorrection;
00354         Transform _lastOdomPose;
00355         bool _processingOdometry;
00356 
00357         QTimer * _oneSecondTimer;
00358         QTime * _elapsedTime;
00359         QTime * _logEventTime;
00360 
00361         PdfPlotCurve * _posteriorCurve;
00362         PdfPlotCurve * _likelihoodCurve;
00363         PdfPlotCurve * _rawLikelihoodCurve;
00364 
00365         ProgressDialog * _progressDialog;
00366 
00367         CloudViewer * _cloudViewer;
00368         LoopClosureViewer * _loopClosureViewer;
00369 
00370         QString _graphSavingFileName;
00371         bool _exportPosesFrame;
00372         QMap<int, QString> _exportPosesFileName;
00373         bool _autoScreenCaptureOdomSync;
00374         bool _autoScreenCaptureRAM;
00375         bool _autoScreenCapturePNG;
00376         QMap<QString, QByteArray> _autoScreenCaptureCachedImages;
00377 
00378         QVector<int> _refIds;
00379         QVector<int> _loopClosureIds;
00380 
00381         bool _firstCall;
00382         bool _progressCanceled;
00383 };
00384 
00385 }
00386 
00387 #endif /* RTABMAP_MainWindow_H_ */


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