Constructs a QT GUI for easy control of RGBD-SLAM. More...
#include <qt_gui.h>
Public Slots | |
void | sendFinished () |
Call to display, that sending finished. | |
void | setDepthImage (QImage) |
void | setFeatureFlowImage (QImage) |
void | setVisualImage (QImage) |
void | showOptions () |
Signals | |
void | deleteLastFrame () |
User wants the last node to be removed from the graph. | |
void | evaluation () |
void | getOneFrame () |
User wants the next frame to be processed. | |
void | optimizeGraph () |
void | printEdgeErrors (QString) |
void | pruneEdgesWithErrorAbove (float) |
void | reset () |
User selected to reset the graph. | |
void | saveAllClouds (QString filename) |
User wants the current world model to be saved to a pcd-file or ply file. | |
void | saveAllFeatures (QString filename) |
void | saveIndividualClouds (QString file_basename) |
User wants the current world model to be saved to one pcd-file per node. | |
void | saveTrajectory (QString filename) |
void | sendAllClouds () |
void | setMaxDepth (float max_depth) |
void | toggleBagRecording () |
User selected to start or resume bag recording. | |
void | toggleMapping (bool) |
void | togglePause () |
User selected to start or resume processing. | |
Public Member Functions | |
GLViewer * | getGLViewer () |
Graphical_UI () | |
Constructs a QT GUI for easy control of RGBDSLAM. | |
Private Slots | |
void | about () |
void | bagRecording (bool) |
void | deleteLastFrameCmd () |
void | getOneFrameCmd () |
void | help () |
void | optimizeGraphTrig () |
void | pause (bool) |
void | pruneEdgesWithHighError () |
void | quickSaveAll () |
void | reloadConfig () |
void | resetCmd () |
void | saveAll () |
void | saveFeatures () |
void | saveIndividual () |
void | saveTrajectoryDialog () |
void | saveVectorGraphic () |
void | sendAll () |
void | set2DStream (bool is_on) |
void | setInfo (QString) |
void | setInfo2 (QString) |
void | setMax () |
void | setRotationGrid () |
void | setStatus (QString) |
void | setStereoShift () |
void | showEdgeErrors () |
void | toggleCloudStorage (bool) |
void | toggleFullscreen (bool) |
void | toggleMappingPriv (bool) |
Private Member Functions | |
void | createMenus () |
Menus and Menu elements are defined here. | |
Private Attributes | |
QLabel * | depth_image_label |
QLabel * | feature_flow_image_label |
QString | filename |
GLViewer * | glviewer |
QGridLayout * | gridlayout |
QLabel * | infoLabel |
QLabel * | infoLabel2 |
QString * | infoText |
QString * | licenseText |
QString * | mouseHelpText |
bool | pause_on |
QLabel * | stats_image_label |
QLabel * | tmpLabel |
QLabel * | visual_image_label |
QSplitter * | vsplitter |
Constructs a QT GUI for easy control of RGBD-SLAM.
Small GUI Class to visualize and control rgbdslam See Help->About for a short description
Constructs a QT GUI for easy control of RGBDSLAM.
Definition at line 37 of file qt_gui.cpp.
void Graphical_UI::about | ( | ) | [private, slot] |
Definition at line 336 of file qt_gui.cpp.
void Graphical_UI::bagRecording | ( | bool | pause_on | ) | [private, slot] |
Definition at line 304 of file qt_gui.cpp.
void Graphical_UI::createMenus | ( | ) | [private] |
Menus and Menu elements are defined here.
Definition at line 369 of file qt_gui.cpp.
void Graphical_UI::deleteLastFrame | ( | ) | [signal] |
User wants the last node to be removed from the graph.
void Graphical_UI::deleteLastFrameCmd | ( | ) | [private, slot] |
Definition at line 293 of file qt_gui.cpp.
void Graphical_UI::evaluation | ( | ) | [signal] |
Definition at line 713 of file qt_gui.cpp.
void Graphical_UI::getOneFrame | ( | ) | [signal] |
User wants the next frame to be processed.
void Graphical_UI::getOneFrameCmd | ( | ) | [private, slot] |
Definition at line 287 of file qt_gui.cpp.
void Graphical_UI::help | ( | ) | [private, slot] |
menuHelpText +
Definition at line 333 of file qt_gui.cpp.
void Graphical_UI::optimizeGraph | ( | ) | [signal] |
void Graphical_UI::optimizeGraphTrig | ( | ) | [private, slot] |
Definition at line 205 of file qt_gui.cpp.
void Graphical_UI::pause | ( | bool | pause_on | ) | [private, slot] |
Definition at line 320 of file qt_gui.cpp.
void Graphical_UI::printEdgeErrors | ( | QString | ) | [signal] |
void Graphical_UI::pruneEdgesWithErrorAbove | ( | float | ) | [signal] |
void Graphical_UI::pruneEdgesWithHighError | ( | ) | [private, slot] |
Definition at line 272 of file qt_gui.cpp.
void Graphical_UI::quickSaveAll | ( | ) | [private, slot] |
Definition at line 176 of file qt_gui.cpp.
void Graphical_UI::reloadConfig | ( | ) | [private, slot] |
Definition at line 150 of file qt_gui.cpp.
void Graphical_UI::reset | ( | ) | [signal] |
User selected to reset the graph.
void Graphical_UI::resetCmd | ( | ) | [private, slot] |
Definition at line 156 of file qt_gui.cpp.
void Graphical_UI::saveAll | ( | ) | [private, slot] |
Definition at line 192 of file qt_gui.cpp.
void Graphical_UI::saveAllClouds | ( | QString | filename | ) | [signal] |
User wants the current world model to be saved to a pcd-file or ply file.
void Graphical_UI::saveAllFeatures | ( | QString | filename | ) | [signal] |
void Graphical_UI::saveFeatures | ( | ) | [private, slot] |
Definition at line 185 of file qt_gui.cpp.
void Graphical_UI::saveIndividual | ( | ) | [private, slot] |
Definition at line 223 of file qt_gui.cpp.
void Graphical_UI::saveIndividualClouds | ( | QString | file_basename | ) | [signal] |
User wants the current world model to be saved to one pcd-file per node.
void Graphical_UI::saveTrajectory | ( | QString | filename | ) | [signal] |
void Graphical_UI::saveTrajectoryDialog | ( | ) | [private, slot] |
Definition at line 217 of file qt_gui.cpp.
void Graphical_UI::saveVectorGraphic | ( | ) | [private, slot] |
Definition at line 210 of file qt_gui.cpp.
void Graphical_UI::sendAll | ( | ) | [private, slot] |
Definition at line 234 of file qt_gui.cpp.
void Graphical_UI::sendAllClouds | ( | ) | [signal] |
Signifies the sending of the whole model
void Graphical_UI::sendFinished | ( | ) | [slot] |
Call to display, that sending finished.
Definition at line 280 of file qt_gui.cpp.
void Graphical_UI::set2DStream | ( | bool | is_on | ) | [private, slot] |
Definition at line 340 of file qt_gui.cpp.
void Graphical_UI::setDepthImage | ( | QImage | qimage | ) | [slot] |
Definition at line 143 of file qt_gui.cpp.
void Graphical_UI::setFeatureFlowImage | ( | QImage | qimage | ) | [slot] |
Definition at line 129 of file qt_gui.cpp.
void Graphical_UI::setInfo | ( | QString | message | ) | [private, slot] |
Definition at line 171 of file qt_gui.cpp.
void Graphical_UI::setInfo2 | ( | QString | message | ) | [private, slot] |
Definition at line 167 of file qt_gui.cpp.
void Graphical_UI::setMax | ( | ) | [private, slot] |
Definition at line 254 of file qt_gui.cpp.
void Graphical_UI::setMaxDepth | ( | float | max_depth | ) | [signal] |
void Graphical_UI::setRotationGrid | ( | ) | [private, slot] |
Definition at line 241 of file qt_gui.cpp.
void Graphical_UI::setStatus | ( | QString | message | ) | [private, slot] |
Definition at line 164 of file qt_gui.cpp.
void Graphical_UI::setStereoShift | ( | ) | [private, slot] |
Definition at line 247 of file qt_gui.cpp.
void Graphical_UI::setVisualImage | ( | QImage | qimage | ) | [slot] |
Definition at line 136 of file qt_gui.cpp.
void Graphical_UI::showEdgeErrors | ( | ) | [private, slot] |
Definition at line 199 of file qt_gui.cpp.
void Graphical_UI::showOptions | ( | ) | [slot] |
Definition at line 717 of file qt_gui.cpp.
void Graphical_UI::toggleBagRecording | ( | ) | [signal] |
User selected to start or resume bag recording.
void Graphical_UI::toggleCloudStorage | ( | bool | storage | ) | [private, slot] |
Definition at line 316 of file qt_gui.cpp.
void Graphical_UI::toggleFullscreen | ( | bool | mode | ) | [private, slot] |
Definition at line 262 of file qt_gui.cpp.
void Graphical_UI::toggleMapping | ( | bool | ) | [signal] |
void Graphical_UI::toggleMappingPriv | ( | bool | mapping_on | ) | [private, slot] |
Definition at line 300 of file qt_gui.cpp.
void Graphical_UI::togglePause | ( | ) | [signal] |
User selected to start or resume processing.
QLabel* Graphical_UI::depth_image_label [private] |
QLabel* Graphical_UI::feature_flow_image_label [private] |
QString Graphical_UI::filename [private] |
GLViewer* Graphical_UI::glviewer [private] |
QGridLayout* Graphical_UI::gridlayout [private] |
QLabel* Graphical_UI::infoLabel [private] |
QLabel* Graphical_UI::infoLabel2 [private] |
QString* Graphical_UI::infoText [private] |
QString* Graphical_UI::licenseText [private] |
QString* Graphical_UI::mouseHelpText [private] |
bool Graphical_UI::pause_on [private] |
QLabel* Graphical_UI::stats_image_label [private] |
QLabel* Graphical_UI::tmpLabel [private] |
QLabel* Graphical_UI::visual_image_label [private] |
QSplitter* Graphical_UI::vsplitter [private] |