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 DBDriver;
00054 class ImageView;
00055 class SensorData;
00056 class CloudViewer;
00057
00058 class RTABMAPGUI_EXP DatabaseViewer : public QMainWindow
00059 {
00060 Q_OBJECT
00061
00062 public:
00063 DatabaseViewer(const QString & ini = QString(), 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 generateG2OGraph();
00086 void view3DMap();
00087 void view3DLaserScans();
00088 void generate3DMap();
00089 void generate3DLaserScans();
00090 void detectMoreLoopClosures();
00091 void refineAllNeighborLinks();
00092 void refineAllLoopClosureLinks();
00093 void refineVisuallyAllNeighborLinks();
00094 void refineVisuallyAllLoopClosureLinks();
00095 void resetAllChanges();
00096 void sliderAValueChanged(int);
00097 void sliderBValueChanged(int);
00098 void sliderAMoved(int);
00099 void sliderBMoved(int);
00100 void update3dView();
00101 void sliderNeighborValueChanged(int);
00102 void sliderLoopValueChanged(int);
00103 void sliderIterationsValueChanged(int);
00104 void updateGrid();
00105 void updateGraphView();
00106 void refineConstraint();
00107 void refineConstraintVisually();
00108 void addConstraint();
00109 void resetConstraint();
00110 void rejectConstraint();
00111 void updateConstraintView();
00112 void updateLoggerLevel();
00113 void updateStereo();
00114 void notifyParametersChanged(const QStringList &);
00115 void setupMainLayout(int vertical);
00116
00117 private:
00118 QString getIniFilePath() const;
00119 void readSettings();
00120
00121 void updateIds();
00122 void update(int value,
00123 QLabel * labelIndex,
00124 QLabel * labelParents,
00125 QLabel * labelChildren,
00126 QLabel * weight,
00127 QLabel * label,
00128 QLabel * stamp,
00129 rtabmap::ImageView * view,
00130 rtabmap::CloudViewer * view3D,
00131 QLabel * labelId,
00132 QLabel * labelMapId,
00133 QLabel * labelPose,
00134 QLabel * labeCalib,
00135 bool updateConstraintView);
00136 void updateStereo(const SensorData * data);
00137 void updateWordsMatching();
00138 void updateConstraintView(
00139 const rtabmap::Link & link,
00140 bool updateImageSliders = true,
00141 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloudFrom = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00142 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloudTo = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00143 const pcl::PointCloud<pcl::PointXYZ>::Ptr & scanFrom = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>),
00144 const pcl::PointCloud<pcl::PointXYZ>::Ptr & scanTo = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
00145 void updateConstraintButtons();
00146 Link findActiveLink(int from, int to);
00147 bool containsLink(
00148 std::multimap<int, Link> & links,
00149 int from,
00150 int to);
00151 std::multimap<int, rtabmap::Link> updateLinksWithModifications(
00152 const std::multimap<int, rtabmap::Link> & edgeConstraints);
00153 void updateLoopClosuresSlider(int from = 0, int to = 0);
00154 void refineConstraint(int from, int to, bool silent, bool updateGraph);
00155 void refineConstraintVisually(int from, int to, bool silent, bool updateGraph);
00156 bool addConstraint(int from, int to, bool silent, bool updateGraph);
00157
00158 private:
00159 Ui_DatabaseViewer * ui_;
00160 CloudViewer * constraintsViewer_;
00161 CloudViewer * cloudViewerA_;
00162 CloudViewer * cloudViewerB_;
00163 CloudViewer * stereoViewer_;
00164 QList<int> ids_;
00165 std::map<int, int> mapIds_;
00166 QMap<int, int> idToIndex_;
00167 QList<rtabmap::Link> neighborLinks_;
00168 QList<rtabmap::Link> loopLinks_;
00169 rtabmap::DBDriver * dbDriver_;
00170 QString pathDatabase_;
00171 std::string databaseFileName_;
00172 std::list<std::map<int, rtabmap::Transform> > graphes_;
00173 std::multimap<int, rtabmap::Link> graphLinks_;
00174 std::map<int, rtabmap::Transform> poses_;
00175 std::map<int, rtabmap::Transform> groundTruthPoses_;
00176 std::multimap<int, rtabmap::Link> links_;
00177 std::multimap<int, rtabmap::Link> linksRefined_;
00178 std::multimap<int, rtabmap::Link> linksAdded_;
00179 std::multimap<int, rtabmap::Link> linksRemoved_;
00180 std::map<int, std::pair<cv::Mat, cv::Mat> > localMaps_;
00181
00182 bool savedMaximized_;
00183 bool firstCall_;
00184 QString iniFilePath_;
00185 };
00186
00187 }
00188
00189 #endif