Constructs a QT GUI for easy control of RGBD-SLAM. More...
#include <qt_gui.h>
Public Slots | |
void | saveAllImages () |
void | sendFinished () |
Call to display, that sending finished. | |
void | set2DStream (bool is_on) |
void | setBusy (int id, const char *message, int val) |
void | setDepthImage (QImage) |
void | setFeatureFlowImage (QImage) |
void | setFeatureImage (QImage) |
void | setVisualImage (QImage) |
void | showBusy (int id, const char *message, int max) |
void | showOptions () |
Signals | |
void | clearClouds () |
void | computeOctomapSig (QString filename) |
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 | occupancyFilterClouds () |
void | openBagFile (QString filename) |
void | openPCDFiles (QStringList filenamelist) |
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 | saveBagfile (QString filename) |
void | saveG2OGraph (QString filename) |
User wants the g2o graph saved. | |
void | saveIndividualClouds (QString file_basename) |
User wants the current world model to be saved to one pcd-file per node. | |
void | saveOctomapSig (QString filename) |
void | saveTrajectory (QString filename) |
void | sendAllClouds () |
Signifies the sending of the whole model. | |
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. | |
Graphical_UI (QString title) | |
Constructs a QT GUI for easy control of RGBDSLAM. | |
Private Slots | |
void | about () |
void | computeOctomap () |
void | deleteLastFrameCmd () |
void | getOneFrameCmd () |
void | help () |
void | openBagFileDialog () |
void | openPCDFilesDialog () |
void | optimizeGraphTrig () |
void | pause (bool) |
void | pruneEdgesWithHighError () |
void | quickSaveAll () |
void | reloadConfig () |
void | resetCmd () |
void | saveAll () |
void | saveBagDialog () |
void | saveFeatures () |
void | saveG2OGraphDialog () |
void | saveIndividual () |
void | saveOctomap () |
void | saveTrajectoryDialog () |
void | saveVectorGraphic () |
void | sendAll () |
void | setInfo (QString) |
void | setInfo2 (QString) |
void | setOctoMapResolution () |
void | setParam () |
Show a combobox to select a parameter, then call this->setParam(QString) | |
void | setParam (QString param_name) |
void | setRotationGrid () |
void | setStatus (QString) |
void | setStereoShift () |
void | showEdgeErrors () |
void | toggleCloudStorage (bool) |
void | toggleFullscreen (bool) |
void | toggleLandmarkOptimization (bool) |
void | toggleMappingPriv (bool) |
void | toggleOnlineVoxelMapping (bool) |
void | toggleScreencast (bool) |
void | triggerCloudFiltering () |
Private Member Functions | |
void | createLoadMenu () |
void | createMenus () |
Menus and Menu elements are defined here. | |
void | createProcessingMenu () |
QAction * | createSaveMenu () |
void | initTexts () |
QAction * | newAction (QMenu *menu, const char *title, const char *statustip, QIcon icon) |
QAction * | newMenuItem (QMenu *menu, const char *title, QObject *receiver, const char *callback, const char *statustip, bool checked, const char *key_seq="", QIcon icon=QIcon()) |
QAction * | newMenuItem (QMenu *menu, const char *title, const char *callback_method_of_this_class, const char *statustip, const char *key_seq="", QIcon icon=QIcon()) |
QAction * | newMenuItem (QMenu *menu, const char *title, const char *callback_method_of_this_class, const char *statustip, QKeySequence::StandardKey key_seq, QIcon icon=QIcon()) |
QAction * | newMenuItem (QMenu *menu, const char *title, QObject *receiver, const char *callback, const char *statustip, const char *key_seq="", QIcon icon=QIcon()) |
void | setLabelToImage (QLabel *which_label, QImage new_image) |
void | setup () |
void | setupStatusbar () |
Private Attributes | |
QLabel * | depth_image_label |
QLabel * | feature_flow_image_label |
QLabel * | feature_image_label |
QString | filename |
GLViewer * | glviewer |
QGridLayout * | gridlayout |
QLabel * | infoLabel |
QLabel * | infoLabel2 |
QString * | infoText |
QString * | licenseText |
QString * | mouseHelpText |
bool | pause_on |
QMap< int, QProgressBar * > | progressbars |
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.
Graphical_UI::Graphical_UI | ( | QString | title | ) |
Constructs a QT GUI for easy control of RGBDSLAM.
Definition at line 43 of file qt_gui.cpp.
void Graphical_UI::about | ( | ) | [private, slot] |
Definition at line 529 of file qt_gui.cpp.
void Graphical_UI::clearClouds | ( | ) | [signal] |
void Graphical_UI::computeOctomap | ( | ) | [private, slot] |
Definition at line 282 of file qt_gui.cpp.
void Graphical_UI::computeOctomapSig | ( | QString | filename | ) | [signal] |
void Graphical_UI::createLoadMenu | ( | ) | [private] |
Definition at line 598 of file qt_gui.cpp.
void Graphical_UI::createMenus | ( | ) | [private] |
Menus and Menu elements are defined here.
Definition at line 746 of file qt_gui.cpp.
void Graphical_UI::createProcessingMenu | ( | ) | [private] |
Definition at line 695 of file qt_gui.cpp.
QAction * Graphical_UI::createSaveMenu | ( | ) | [private] |
Definition at line 615 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 489 of file qt_gui.cpp.
void Graphical_UI::evaluation | ( | ) | [signal] |
Definition at line 980 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 484 of file qt_gui.cpp.
void Graphical_UI::help | ( | ) | [private, slot] |
menuHelpText +
Definition at line 526 of file qt_gui.cpp.
void Graphical_UI::initTexts | ( | ) | [private] |
Definition at line 61 of file qt_gui.cpp.
QAction * Graphical_UI::newAction | ( | QMenu * | menu, |
const char * | title, | ||
const char * | statustip, | ||
QIcon | icon | ||
) | [private] |
Definition at line 562 of file qt_gui.cpp.
QAction * Graphical_UI::newMenuItem | ( | QMenu * | menu, |
const char * | title, | ||
QObject * | receiver, | ||
const char * | callback, | ||
const char * | statustip, | ||
bool | checked, | ||
const char * | key_seq = "" , |
||
QIcon | icon = QIcon() |
||
) | [private] |
Definition at line 589 of file qt_gui.cpp.
QAction * Graphical_UI::newMenuItem | ( | QMenu * | menu, |
const char * | title, | ||
const char * | callback_method_of_this_class, | ||
const char * | statustip, | ||
const char * | key_seq = "" , |
||
QIcon | icon = QIcon() |
||
) | [private] |
Definition at line 583 of file qt_gui.cpp.
QAction * Graphical_UI::newMenuItem | ( | QMenu * | menu, |
const char * | title, | ||
const char * | callback_method_of_this_class, | ||
const char * | statustip, | ||
QKeySequence::StandardKey | key_seq, | ||
QIcon | icon = QIcon() |
||
) | [private] |
Definition at line 577 of file qt_gui.cpp.
QAction * Graphical_UI::newMenuItem | ( | QMenu * | menu, |
const char * | title, | ||
QObject * | receiver, | ||
const char * | callback, | ||
const char * | statustip, | ||
const char * | key_seq = "" , |
||
QIcon | icon = QIcon() |
||
) | [private] |
Definition at line 571 of file qt_gui.cpp.
void Graphical_UI::occupancyFilterClouds | ( | ) | [signal] |
void Graphical_UI::openBagFile | ( | QString | filename | ) | [signal] |
void Graphical_UI::openBagFileDialog | ( | ) | [private, slot] |
Definition at line 242 of file qt_gui.cpp.
void Graphical_UI::openPCDFiles | ( | QStringList | filenamelist | ) | [signal] |
void Graphical_UI::openPCDFilesDialog | ( | ) | [private, slot] |
Definition at line 255 of file qt_gui.cpp.
void Graphical_UI::optimizeGraph | ( | ) | [signal] |
void Graphical_UI::optimizeGraphTrig | ( | ) | [private, slot] |
Definition at line 312 of file qt_gui.cpp.
void Graphical_UI::pause | ( | bool | pause_on | ) | [private, slot] |
Definition at line 515 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 470 of file qt_gui.cpp.
void Graphical_UI::quickSaveAll | ( | ) | [private, slot] |
Definition at line 233 of file qt_gui.cpp.
void Graphical_UI::reloadConfig | ( | ) | [private, slot] |
Definition at line 194 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 200 of file qt_gui.cpp.
void Graphical_UI::saveAll | ( | ) | [private, slot] |
Definition at line 298 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::saveAllImages | ( | ) | [slot] |
Definition at line 1092 of file qt_gui.cpp.
void Graphical_UI::saveBagDialog | ( | ) | [private, slot] |
Definition at line 361 of file qt_gui.cpp.
void Graphical_UI::saveBagfile | ( | QString | filename | ) | [signal] |
Signifies the sending of the whole model
void Graphical_UI::saveFeatures | ( | ) | [private, slot] |
Definition at line 269 of file qt_gui.cpp.
void Graphical_UI::saveG2OGraph | ( | QString | filename | ) | [signal] |
User wants the g2o graph saved.
void Graphical_UI::saveG2OGraphDialog | ( | ) | [private, slot] |
Definition at line 220 of file qt_gui.cpp.
void Graphical_UI::saveIndividual | ( | ) | [private, slot] |
Definition at line 348 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::saveOctomap | ( | ) | [private, slot] |
Definition at line 286 of file qt_gui.cpp.
void Graphical_UI::saveOctomapSig | ( | QString | filename | ) | [signal] |
void Graphical_UI::saveTrajectory | ( | QString | filename | ) | [signal] |
void Graphical_UI::saveTrajectoryDialog | ( | ) | [private, slot] |
Definition at line 342 of file qt_gui.cpp.
void Graphical_UI::saveVectorGraphic | ( | ) | [private, slot] |
Definition at line 318 of file qt_gui.cpp.
void Graphical_UI::sendAll | ( | ) | [private, slot] |
Definition at line 367 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 478 of file qt_gui.cpp.
void Graphical_UI::set2DStream | ( | bool | is_on | ) | [slot] |
Definition at line 533 of file qt_gui.cpp.
void Graphical_UI::setBusy | ( | int | id, |
const char * | message, | ||
int | val | ||
) | [slot] |
Definition at line 1072 of file qt_gui.cpp.
void Graphical_UI::setDepthImage | ( | QImage | qimage | ) | [slot] |
Definition at line 190 of file qt_gui.cpp.
void Graphical_UI::setFeatureFlowImage | ( | QImage | qimage | ) | [slot] |
Definition at line 182 of file qt_gui.cpp.
void Graphical_UI::setFeatureImage | ( | QImage | qimage | ) | [slot] |
Definition at line 178 of file qt_gui.cpp.
void Graphical_UI::setInfo | ( | QString | message | ) | [private, slot] |
Definition at line 215 of file qt_gui.cpp.
void Graphical_UI::setInfo2 | ( | QString | message | ) | [private, slot] |
Definition at line 211 of file qt_gui.cpp.
void Graphical_UI::setLabelToImage | ( | QLabel * | which_label, |
QImage | new_image | ||
) | [private] |
Definition at line 167 of file qt_gui.cpp.
void Graphical_UI::setOctoMapResolution | ( | ) | [private, slot] |
Definition at line 502 of file qt_gui.cpp.
void Graphical_UI::setParam | ( | ) | [private, slot] |
Show a combobox to select a parameter, then call this->setParam(QString)
Definition at line 440 of file qt_gui.cpp.
void Graphical_UI::setParam | ( | QString | param_name | ) | [private, slot] |
Definition at line 386 of file qt_gui.cpp.
void Graphical_UI::setRotationGrid | ( | ) | [private, slot] |
Definition at line 373 of file qt_gui.cpp.
void Graphical_UI::setStatus | ( | QString | message | ) | [private, slot] |
Definition at line 208 of file qt_gui.cpp.
void Graphical_UI::setStereoShift | ( | ) | [private, slot] |
Definition at line 379 of file qt_gui.cpp.
void Graphical_UI::setup | ( | ) | [private] |
Definition at line 92 of file qt_gui.cpp.
void Graphical_UI::setupStatusbar | ( | ) | [private] |
Definition at line 143 of file qt_gui.cpp.
void Graphical_UI::setVisualImage | ( | QImage | qimage | ) | [slot] |
Definition at line 186 of file qt_gui.cpp.
void Graphical_UI::showBusy | ( | int | id, |
const char * | message, | ||
int | max | ||
) | [slot] |
Definition at line 1055 of file qt_gui.cpp.
void Graphical_UI::showEdgeErrors | ( | ) | [private, slot] |
Definition at line 305 of file qt_gui.cpp.
void Graphical_UI::showOptions | ( | ) | [slot] |
Definition at line 984 of file qt_gui.cpp.
void Graphical_UI::toggleCloudStorage | ( | bool | storage | ) | [private, slot] |
Definition at line 508 of file qt_gui.cpp.
void Graphical_UI::toggleFullscreen | ( | bool | mode | ) | [private, slot] |
Definition at line 460 of file qt_gui.cpp.
void Graphical_UI::toggleLandmarkOptimization | ( | bool | landmarks | ) | [private, slot] |
Definition at line 511 of file qt_gui.cpp.
void Graphical_UI::toggleMapping | ( | bool | ) | [signal] |
void Graphical_UI::toggleMappingPriv | ( | bool | mapping_on | ) | [private, slot] |
Definition at line 495 of file qt_gui.cpp.
void Graphical_UI::toggleOnlineVoxelMapping | ( | bool | online | ) | [private, slot] |
Definition at line 505 of file qt_gui.cpp.
void Graphical_UI::togglePause | ( | ) | [signal] |
User selected to start or resume processing.
void Graphical_UI::toggleScreencast | ( | bool | on | ) | [private, slot] |
Definition at line 329 of file qt_gui.cpp.
void Graphical_UI::triggerCloudFiltering | ( | ) | [private, slot] |
Definition at line 499 of file qt_gui.cpp.
QLabel* Graphical_UI::depth_image_label [private] |
QLabel* Graphical_UI::feature_flow_image_label [private] |
QLabel* Graphical_UI::feature_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] |
QMap<int, QProgressBar*> Graphical_UI::progressbars [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] |