qt_gui.h
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 
00017 
00018 /* This is the main widget of the application.
00019 * It sets up some not yet useful menus and
00020 * three qlabels in the layout of the central widget
00021 * that can be used to show qimages via the slots
00022 * setDepthImage and setVisualImage.
00023 *
00024 * there is an alternative: RosUI for headless use of the rgbdslam
00025 */
00026 #ifndef QTCV_H
00027 #define QTCV_H
00028 
00029 #include <QMainWindow>
00030 #include <QGridLayout>
00031 #include "parameter_server.h"
00032 #include <QMatrix4x4>
00033 #include <QMap>
00034 
00035 class QAction;
00036 class QActionGroup;
00037 class QLabel;
00038 class QMenu;
00039 class GLViewer;
00040 class QSplitter;
00041 class QProgressBar;
00042 
00043 //TODO:
00044 //Choice between Binary and ASCII outputfiles
00045 //Buttons for start/stop
00046 //GUI/Commandline options for switching on/off the individual visualizations
00047 
00049 
00051 class Graphical_UI: public QMainWindow
00052 {
00053     Q_OBJECT
00054 
00055 public:
00056     Graphical_UI();
00057     Graphical_UI(QString title);
00058     GLViewer* getGLViewer();
00059 Q_SIGNALS:
00061     void reset(); 
00063     void togglePause();
00065     void getOneFrame();
00067     void deleteLastFrame();
00068     void sendAllClouds(); 
00069     void saveBagfile(QString filename); 
00070 
00071     void saveAllClouds(QString filename);
00072     void openPCDFiles(QStringList filenamelist);
00073     void openBagFile(QString filename);
00075     void saveG2OGraph(QString filename);
00076     void saveAllFeatures(QString filename);
00077     void saveTrajectory(QString filename);
00078     void saveOctomapSig(QString filename);
00079     void computeOctomapSig(QString filename);
00081     void saveIndividualClouds(QString file_basename);
00082     void evaluation();
00083     void optimizeGraph();
00084     void occupancyFilterClouds();
00085     void printEdgeErrors(QString);
00086     void pruneEdgesWithErrorAbove(float);
00087     void toggleMapping(bool);
00088     void clearClouds();
00089      
00090 public Q_SLOTS:
00091     void setVisualImage(QImage);
00092     void setFeatureFlowImage(QImage);
00093     void setFeatureImage(QImage);
00094     void setDepthImage(QImage);
00095     void sendFinished(); 
00096     void showOptions();
00097     void showBusy(int id, const char* message, int max);
00098     void setBusy(int id, const char* message, int val);
00099     void set2DStream(bool is_on);
00100     //save depth color feature and correspondences image
00101     void saveAllImages();
00102 
00103 private Q_SLOTS:
00104     void saveVectorGraphic();
00105     void resetCmd();
00106     void reloadConfig();
00107     void sendAll();
00108     void setParam();
00109     void setStereoShift();
00110     void setRotationGrid();
00111     void saveAll();
00112     void saveOctomap();
00113     void computeOctomap();
00114     void saveIndividual();
00115     void quickSaveAll();
00116     void saveFeatures();
00117     void pause(bool);
00118     void about();
00119     void help();
00120     void setInfo(QString);
00121     void setInfo2(QString);
00122     void setStatus(QString);
00123     void getOneFrameCmd();
00124     void deleteLastFrameCmd();
00125 //    void set3DDisplay(bool is_on);
00126     void saveTrajectoryDialog();
00127     void openBagFileDialog();
00128     void saveBagDialog();
00129     void openPCDFilesDialog();
00130     void saveG2OGraphDialog();
00131     void optimizeGraphTrig();
00132     void showEdgeErrors();
00133     void pruneEdgesWithHighError();
00134     void toggleFullscreen(bool);
00135     void toggleCloudStorage(bool);
00136     void toggleOnlineVoxelMapping(bool);
00137     void toggleLandmarkOptimization(bool);
00138     void toggleMappingPriv(bool);
00139     void toggleScreencast(bool);
00140     //Display a Dialog to change the value of the mentioned parameter
00141     void setParam(QString param_name);
00142     void setOctoMapResolution();
00143     void triggerCloudFiltering();
00144 private:
00145     //Helper to add a new checkable item to a menu. Assumes callback is method of this class
00146     QAction* newMenuItem(QMenu* menu, const char* title, QObject* receiver, const char* callback, const char* statustip, bool checked, const char* key_seq = "" ,QIcon icon = QIcon());
00147     //Helper to add a new item to a menu. Assumes callback is method of this class
00148     QAction* newMenuItem(QMenu* menu, const char* title, const char* callback_method_of_this_class, const char* statustip,               const char* key_seq = "", QIcon icon = QIcon());
00149     //Helper to add a new item to a menu. Assumes callback is method of this class
00150     QAction* newMenuItem(QMenu* menu, const char* title, const char* callback_method_of_this_class, const char* statustip, QKeySequence::StandardKey key_seq,      QIcon icon = QIcon());
00151     //Helper to add a new item to a menu. 
00152     QAction* newMenuItem(QMenu* menu, const char* title, QObject* receiver, const char* callback,   const char* statustip,               const char* key_seq = "", QIcon icon = QIcon());
00153     //Helper for newMenuItem
00154     QAction* newAction(QMenu* menu, const char* title, const char* statustip, QIcon icon);
00155     void setLabelToImage(QLabel* which_label, QImage new_image);
00156     void setup();
00157     void setupStatusbar();
00158     void initTexts();
00160     void createMenus();
00161     //create "save" menu, return saveOctomap to also put in octoMapMenu
00162     QAction* createSaveMenu();
00163     void createProcessingMenu();
00164     void createLoadMenu();
00165     //QString *menuHelpText;
00166     QString *mouseHelpText;
00167     QString *infoText;
00168     QString *licenseText;
00169     QSplitter* vsplitter;
00170     QLabel *infoLabel;
00171     QLabel *infoLabel2;
00172     QLabel *tmpLabel;
00173     QLabel *visual_image_label;
00174     QLabel *feature_flow_image_label;
00175     QLabel *depth_image_label;
00176     QLabel *feature_image_label;
00177     QLabel *stats_image_label;
00178     //QLabel *transform_label;
00179     QGridLayout* gridlayout;
00180     QString filename;
00181     GLViewer* glviewer;
00182     bool pause_on;
00183     QMap<int, QProgressBar*> progressbars;
00184 };
00185 
00186 #endif


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45