28 #include <QtGui/QMainWindow> 29 #include <QFileDialog> 30 #include <QMessageBox> 31 #include <QDockWidget> 42 #include "ui_ViewerGui.h" 54 ViewerGui(
const std::string& filename=
"", QWidget *parent = 0);
126 void changeCamPosition(
double x,
double y,
double z,
double lookX,
double lookY,
double lookZ);
145 void openGraph(
bool completeGraph =
true);
150 void loadGraph(
bool completeGraph =
true);
181 void showInfo(QString
string,
bool newline=
false);
199 Ui::ViewerGuiClass
ui;
220 #endif // VIEWERGUI_H
void on_actionRestore_camera_triggered()
QLabel * m_mapMemoryStatus
ViewerWidget * m_glwidget
ScanGraph::iterator m_nextScanToAdd
static const unsigned int LASERTYPE_URG
void on_actionStore_camera_triggered()
void on_actionOctree_cells_toggled(bool enabled)
void openOcTree()
open "regular" file containing an octree
void on_action_bg_black_triggered()
double m_octreeResolution
void on_actionTest_triggered()
void loadGraph(bool completeGraph=true)
void openGraph(bool completeGraph=true)
void changeCurrentScan(unsigned scans)
void on_actionClear_selection_triggered()
void addNextScans(unsigned scans)
void on_actionClear_unknown_in_selection_triggered()
void on_action_bg_white_triggered()
void on_actionReload_Octree_triggered()
void on_actionSemanticColoring_toggled(bool checked)
void saveCameraPosition(const char *filename) const
void changeNumberOfScans(unsigned scans)
void on_actionFill_nodes_in_selection_triggered()
void on_actionSave_file_triggered()
void on_actionFree_toggled(bool enabled)
std::string m_filename
Filename of last loaded file, in case it is necessary to reload it.
void on_actionHideBackground_toggled(bool checked)
void on_actionClear_nodes_in_selection_triggered()
void updateNodesInBBX(const point3d &min, const point3d &max, bool occupied)
void on_actionDelete_nodes_outside_of_selection_triggered()
TrajectoryDrawer * m_trajectoryDrawer
void on_actionAxes_toggled(bool checked)
static const unsigned int LASERTYPE_SICK
void showInfo(QString string, bool newline=false)
std::vector< ScanNode * >::iterator iterator
ViewerGui(const std::string &filename="", QWidget *parent=0)
void on_actionClear_triggered()
void on_actionFill_selection_triggered()
void addOctree(AbstractOcTree *tree, int id, pose6d origin)
void on_actionExport_view_triggered()
void on_actionHeight_map_toggled(bool checked)
void on_action_bg_gray_triggered()
void changeResolution(double resolution)
void on_savecampose_triggered()
void on_actionSelection_box_toggled(bool checked)
void setNonNodesInBBX(const point3d &min, const point3d &max, bool occupied)
unsigned int m_max_tree_depth
void on_actionPrune_tree_triggered()
void on_actionExport_sequence_triggered(bool checked)
void on_actionDelete_nodes_in_selection_triggered()
void on_actionTrajectory_toggled(bool checked)
void on_actionOpen_graph_incremental_triggered()
void on_actionSettings_triggered()
void on_actionExit_triggered()
CameraFollowMode * m_cameraFollowMode
void updateStatusBar(QString message, int duration)
void setOcTreeUISwitches()
void on_loadcampose_triggered()
PointcloudDrawer * m_pointcloudDrawer
void on_actionOpen_file_triggered()
void on_actionSelected_toggled(bool enabled)
void on_actionOctree_structure_toggled(bool enabled)
static const unsigned int DEFAULT_OCTREE_ID
void setNodesInBBX(const point3d &min, const point3d &max, bool occupied)
void loadCameraPosition(const char *filename)
std::map< int, OcTreeRecord > m_octrees
void on_actionPrintout_mode_toggled(bool checked)
void on_actionFill_unknown_in_selection_triggered()
void on_actionHelp_triggered()
void changeTreeDepth(int depth)
bool getOctreeRecord(int id, OcTreeRecord *&otr)
void on_actionConvert_ml_tree_triggered()
void changeCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ)
void on_actionPointcloud_toggled(bool checked)
void on_actionExpand_tree_triggered()
void openTree()
open binary format OcTree