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 #ifndef VIEWERGUI_H
00027 #define VIEWERGUI_H
00028
00029 #include <QtGui/QMainWindow>
00030 #include <QFileDialog>
00031 #include <QMessageBox>
00032 #include <QDockWidget>
00033 #include <string>
00034 #include <cmath>
00035 #include "TrajectoryDrawer.h"
00036 #include "PointcloudDrawer.h"
00037 #include "OcTreeDrawer.h"
00038 #include "CameraFollowMode.h"
00039 #include "ViewerWidget.h"
00040 #include "ViewerSettings.h"
00041 #include "ViewerSettingsPanel.h"
00042 #include "ViewerSettingsPanelCamera.h"
00043 #include "ui_ViewerGui.h"
00044
00045 #include <octomap/AbstractOcTree.h>
00046 #include <octomap/OcTreeBase.h>
00047 #include <octovis/OcTreeRecord.h>
00048
00049 namespace octomap {
00050
00051 class ViewerGui : public QMainWindow {
00052 Q_OBJECT
00053
00054 public:
00055 ViewerGui(const std::string& filename="", QWidget *parent = 0);
00056 ~ViewerGui();
00057
00058 static const unsigned int LASERTYPE_URG = 0;
00059 static const unsigned int LASERTYPE_SICK = 1;
00060
00061
00062 static const unsigned int DEFAULT_OCTREE_ID = 0;
00063
00064 public slots:
00065
00066 void changeTreeDepth(int depth);
00067 void addNextScans(unsigned scans);
00068 void gotoFirstScan();
00069
00070 bool isShown();
00071
00072 private slots:
00073
00074
00075
00076 void on_actionExit_triggered();
00077 void on_actionOpen_file_triggered();
00078 void on_actionOpen_graph_incremental_triggered();
00079 void on_actionSave_file_triggered();
00080 void on_actionExport_view_triggered();
00081 void on_actionExport_sequence_triggered(bool checked);
00082 void on_actionClear_selection_triggered();
00083 void on_actionFill_selection_triggered();
00084 void on_actionClear_unknown_in_selection_triggered();
00085 void on_actionFill_unknown_in_selection_triggered();
00086 void on_actionClear_nodes_in_selection_triggered();
00087 void on_actionFill_nodes_in_selection_triggered();
00088 void on_actionDelete_nodes_in_selection_triggered();
00089 void on_actionDelete_nodes_outside_of_selection_triggered();
00090 void on_actionHelp_triggered();
00091 void on_actionSettings_triggered();
00092 void on_actionPrune_tree_triggered();
00093 void on_actionExpand_tree_triggered();
00094 void on_actionConvert_ml_tree_triggered();
00095 void on_actionReload_Octree_triggered();
00096 void on_actionPrintout_mode_toggled(bool checked);
00097 void on_actionSelection_box_toggled(bool checked);
00098 void on_actionHeight_map_toggled(bool checked);
00099 void on_actionSemanticColoring_toggled(bool checked);
00100 void on_actionStore_camera_triggered();
00101 void on_actionRestore_camera_triggered();
00102 void on_actionPointcloud_toggled(bool checked);
00103 void on_actionTrajectory_toggled(bool checked);
00104 void on_actionOctree_cells_toggled(bool enabled);
00105 void on_actionOctree_structure_toggled(bool enabled);
00106 void on_actionFree_toggled(bool enabled);
00107 void on_actionSelected_toggled(bool enabled);
00108 void on_actionAxes_toggled(bool checked);
00109 void on_actionHideBackground_toggled(bool checked);
00110 void on_actionClear_triggered();
00111
00112 void on_action_bg_black_triggered();
00113 void on_action_bg_white_triggered();
00114 void on_action_bg_gray_triggered();
00115
00116 void on_savecampose_triggered();
00117 void on_loadcampose_triggered();
00118
00119
00120 void on_actionTest_triggered();
00121
00122 signals:
00123 void updateStatusBar(QString message, int duration);
00124 void changeNumberOfScans(unsigned scans);
00125 void changeCurrentScan(unsigned scans);
00126 void changeResolution(double resolution);
00127 void changeCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ);
00128
00129 private:
00134 void openFile();
00135
00140 void openPointcloud();
00141
00146 void openGraph(bool completeGraph = true);
00147
00151 void loadGraph(bool completeGraph = true);
00152
00156 void addNextScan();
00157
00161 void openPC();
00162
00164 void openOcTree();
00165
00167 void openTree();
00168
00169
00170
00171 void openMapCollection();
00172
00173
00174 void setOcTreeUISwitches();
00175
00179 void generateOctree();
00180 void showOcTree();
00181
00182 void showInfo(QString string, bool newline=false);
00183
00184 void addOctree(AbstractOcTree* tree, int id, pose6d origin);
00185 void addOctree(AbstractOcTree* tree, int id);
00186 bool getOctreeRecord(int id, OcTreeRecord*& otr);
00187
00188 void saveCameraPosition(const char* filename) const;
00189 void loadCameraPosition(const char* filename);
00190
00191 void updateNodesInBBX(const point3d& min, const point3d& max, bool occupied);
00192 void setNodesInBBX(const point3d& min, const point3d& max, bool occupied);
00193 void setNonNodesInBBX(const point3d& min, const point3d& max, bool occupied);
00194
00195 std::map<int, OcTreeRecord> m_octrees;
00196
00197 ScanGraph* m_scanGraph;
00198 ScanGraph::iterator m_nextScanToAdd;
00199
00200 Ui::ViewerGuiClass ui;
00201 ViewerWidget* m_glwidget;
00202 TrajectoryDrawer* m_trajectoryDrawer;
00203 PointcloudDrawer* m_pointcloudDrawer;
00204 CameraFollowMode* m_cameraFollowMode;
00205 double m_octreeResolution;
00206 double m_laserMaxRange;
00207 double m_occupancyThresh;
00208 unsigned int m_max_tree_depth;
00209 unsigned int m_laserType;
00210 bool m_cameraStored;
00211 QLabel* m_mapSizeStatus;
00212 QLabel* m_mapMemoryStatus;
00213
00215 std::string m_filename;
00216 };
00217
00218 }
00219
00220
00221 #endif // VIEWERGUI_H