Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef DATABASEVIEWER_H_
00029 #define DATABASEVIEWER_H_
00030
00031 #include "rtabmap/gui/RtabmapGuiExp.h"
00032
00033 #include <QMainWindow>
00034 #include <QtCore/QByteArray>
00035 #include <QtCore/QMap>
00036 #include <QtCore/QSet>
00037 #include <QtGui/QImage>
00038 #include <opencv2/core/core.hpp>
00039 #include <opencv2/features2d/features2d.hpp>
00040 #include <set>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043
00044 #include <rtabmap/core/Link.h>
00045
00046 class Ui_DatabaseViewer;
00047 class QGraphicsScene;
00048 class QGraphicsView;
00049 class QLabel;
00050
00051 namespace rtabmap
00052 {
00053 class Memory;
00054 class ImageView;
00055 class Signature;
00056 class CloudViewer;
00057
00058 class RTABMAPGUI_EXP DatabaseViewer : public QMainWindow
00059 {
00060 Q_OBJECT
00061
00062 public:
00063 DatabaseViewer(QWidget * parent = 0);
00064 virtual ~DatabaseViewer();
00065 bool openDatabase(const QString & path);
00066 bool isSavedMaximized() const {return savedMaximized_;}
00067 void showCloseButton(bool visible = true);
00068
00069 protected:
00070 virtual void showEvent(QShowEvent* anEvent);
00071 virtual void moveEvent(QMoveEvent* anEvent);
00072 virtual void resizeEvent(QResizeEvent* anEvent);
00073 virtual void closeEvent(QCloseEvent* event);
00074 virtual bool eventFilter(QObject *obj, QEvent *event);
00075
00076 private slots:
00077 void writeSettings();
00078 void configModified();
00079 void openDatabase();
00080 void generateGraph();
00081 void exportDatabase();
00082 void extractImages();
00083 void generateLocalGraph();
00084 void generateTOROGraph();
00085 void view3DMap();
00086 void generate3DMap();
00087 void detectMoreLoopClosures();
00088 void refineAllNeighborLinks();
00089 void refineAllLoopClosureLinks();
00090 void refineVisuallyAllNeighborLinks();
00091 void refineVisuallyAllLoopClosureLinks();
00092 void resetAllChanges();
00093 void sliderAValueChanged(int);
00094 void sliderBValueChanged(int);
00095 void sliderAMoved(int);
00096 void sliderBMoved(int);
00097 void sliderNeighborValueChanged(int);
00098 void sliderLoopValueChanged(int);
00099 void sliderIterationsValueChanged(int);
00100 void updateGrid();
00101 void updateGraphView();
00102 void refineConstraint();
00103 void refineConstraintVisually();
00104 void addConstraint();
00105 void resetConstraint();
00106 void rejectConstraint();
00107 void updateConstraintView();
00108
00109 private:
00110 QString getIniFilePath() const;
00111 void readSettings();
00112
00113 void updateIds();
00114 void update(int value,
00115 QLabel * labelIndex,
00116 QLabel * labelParents,
00117 QLabel * labelChildren,
00118 QLabel * weight,
00119 QLabel * label,
00120 QLabel * stamp,
00121 rtabmap::ImageView * view,
00122 rtabmap::CloudViewer * view3D,
00123 QLabel * labelId,
00124 QLabel * labelMapId,
00125 bool updateConstraintView);
00126 void updateStereo(const Signature * data);
00127 void updateWordsMatching();
00128 void updateConstraintView(
00129 const rtabmap::Link & link,
00130 bool updateImageSliders = true,
00131 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloudFrom = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00132 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloudTo = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00133 const pcl::PointCloud<pcl::PointXYZ>::Ptr & scanFrom = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00134 const pcl::PointCloud<pcl::PointXYZ>::Ptr & scanTo = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
00135 void updateConstraintButtons();
00136 Link findActiveLink(int from, int to);
00137 bool containsLink(
00138 std::multimap<int, Link> & links,
00139 int from,
00140 int to);
00141 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
00142 const std::multimap<int, rtabmap::Link> & edgeConstraints);
00143 void updateLoopClosuresSlider(int from = 0, int to = 0);
00144 void refineConstraint(int from, int to, bool silent, bool updateGraph);
00145 void refineConstraintVisually(int from, int to, bool silent, bool updateGraph);
00146 bool addConstraint(int from, int to, bool silent, bool updateGraph);
00147
00148 private:
00149 Ui_DatabaseViewer * ui_;
00150 QList<int> ids_;
00151 QMap<int, int> idToIndex_;
00152 QList<rtabmap::Link> neighborLinks_;
00153 QList<rtabmap::Link> loopLinks_;
00154 rtabmap::Memory * memory_;
00155 QString pathDatabase_;
00156 std::list<std::map<int, rtabmap::Transform> > graphes_;
00157 std::map<int, rtabmap::Transform> poses_;
00158 std::multimap<int, rtabmap::Link> links_;
00159 std::multimap<int, rtabmap::Link> linksRefined_;
00160 std::multimap<int, rtabmap::Link> linksAdded_;
00161 std::multimap<int, rtabmap::Link> linksRemoved_;
00162 std::map<int, std::pair<cv::Mat, cv::Mat> > localMaps_;
00163
00164 bool savedMaximized_;
00165 bool firstCall_;
00166 };
00167
00168 }
00169
00170 #endif