00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include <QtGui>
00025 #include <QDir>
00026 #include <QPixmap>
00027 #include <QFont>
00028 #include <QList>
00029 #include <QList>
00030 #include <QIcon>
00031 #include <QKeySequence>
00032 #include "qt_gui.h"
00033 #include <limits>
00034 #include "glviewer.h"
00035
00037 Graphical_UI::Graphical_UI() : filename("quicksave.pcd"), glviewer(NULL)
00038 {
00039 infoText = new QString(tr(
00040 "<p><b>RGBDSLAM</b> uses visual features to identify corresponding 3D locations "
00041 "in RGBD data. The correspondences are used to reconstruct the camera motion. "
00042 "The SLAM-backend g2o is used to integrate the transformations between"
00043 "the RGBD-images and compute a globally consistent 6D trajectory.</p>"
00044 "<p></p>"));
00045 licenseText = new QString(tr(
00046 "<p>RGBDSLAM is free software: you can redistribute it and/or modify"
00047 "it under the terms of the GNU General Public License as published by"
00048 "the Free Software Foundation, either version 3 of the License, or"
00049 "(at your option) any later version.</p>"
00050 "<p>RGBDSLAM is distributed in the hope that it will be useful,"
00051 "but WITHOUT ANY WARRANTY; without even the implied warranty of"
00052 "MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the"
00053 "GNU General Public License for more details.</p>"
00054 "<p>You should have received a copy of the GNU General Public License"
00055 "along with RGBDSLAM. If not, refer to <a href=\"http://www.gnu.org/licenses/\">http://www.gnu.org/licenses</a>.</p>"));
00056 mouseHelpText = new QString(tr(
00057 "<p><b>3D Viewer Mouse Commands:</b>"
00058 "<ul><li><i>Left/Right button:</i> rotation.</li>"
00059 " <li><i>Middle button:</i> shift.</li>"
00060 " <li><i>Wheel:</i> zoom.</li>"
00061 " <li><i>Middle double click:</i> reset camera position.</li>"
00062 " <li><i>Double click on object:</i> set pivot to clicked point.</li>"
00063 " <li><i>Double click on background:</i> reset view to camera pose.</li><ul></p>")); feature_flow_image_label = new QLabel(*mouseHelpText);
00064
00065 feature_flow_image_label->setWordWrap(true);
00066 feature_flow_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
00067 if(ParameterServer::instance()->get<bool>("scalable_2d_display"))
00068 feature_flow_image_label->setScaledContents(true);
00069 visual_image_label = new QLabel("<i>Waiting for monochrome image...</i>");
00070 visual_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
00071 visual_image_label->setAlignment(Qt::AlignCenter);
00072 if(ParameterServer::instance()->get<bool>("scalable_2d_display"))
00073 visual_image_label->setScaledContents(true);
00074 depth_image_label = new QLabel(tr("<i>Waiting for depth image...</i>"));
00075 depth_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
00076 depth_image_label->setAlignment(Qt::AlignCenter);
00077 if(ParameterServer::instance()->get<bool>("scalable_2d_display"))
00078 depth_image_label->setScaledContents(true);
00079
00080
00081
00082 if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer = new GLViewer(this);
00083
00084
00085
00086
00087
00088
00089
00090 vsplitter = new QSplitter(Qt::Vertical);
00091 setCentralWidget(vsplitter);
00092
00093 if(ParameterServer::instance()->get<bool>("use_glwidget")) vsplitter->addWidget(glviewer);
00094
00095
00096 QSplitter* hsplitter = new QSplitter(Qt::Horizontal);
00097
00098
00099 hsplitter->addWidget(visual_image_label);
00100 hsplitter->addWidget(depth_image_label);
00101 hsplitter->addWidget(feature_flow_image_label);
00102
00103
00104
00105 vsplitter->addWidget(hsplitter);
00106
00107 createMenus();
00108
00109 tmpLabel = new QLabel();
00110 statusBar()->insertWidget(0,tmpLabel, 0);
00111 QString message = tr("Ready for RGBDSLAM");
00112 statusBar()->showMessage(message);
00113
00114 infoLabel2 = new QLabel(tr("Waiting for motion information..."));
00115 infoLabel2->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
00116 infoLabel2->setAlignment(Qt::AlignRight);
00117 statusBar()->addPermanentWidget(infoLabel2, 0);
00118
00119 infoLabel = new QLabel(tr("<i>Press Enter or Space to Start</i>"));
00120 infoLabel->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
00121 infoLabel->setAlignment(Qt::AlignRight);
00122 statusBar()->addPermanentWidget(infoLabel, 0);
00123
00124 setWindowTitle(tr("RGBDSLAM"));
00125 setMinimumSize(790, 590);
00126 resize(1000, 700);
00127 }
00128
00129 void Graphical_UI::setFeatureFlowImage(QImage qimage){
00130 if(feature_flow_image_label->isVisible()){
00131 feature_flow_image_label->setAlignment(Qt::AlignCenter);
00132 feature_flow_image_label->setPixmap(QPixmap::fromImage(qimage));
00133 feature_flow_image_label->repaint();
00134 }
00135 }
00136 void Graphical_UI::setVisualImage(QImage qimage){
00137 if(visual_image_label->isVisible()){
00138 visual_image_label->setPixmap(QPixmap::fromImage(qimage));
00139 visual_image_label->repaint();
00140 }
00141 }
00142
00143 void Graphical_UI::setDepthImage(QImage qimage){
00144 if(depth_image_label->isVisible()){
00145 depth_image_label->setPixmap(QPixmap::fromImage(qimage));
00146 depth_image_label->repaint();
00147 }
00148 }
00149
00150 void Graphical_UI::reloadConfig() {
00151 ParameterServer::instance()->getValues();
00152 QString message = tr("Configuration Reloaded");
00153 statusBar()->showMessage(message);
00154 }
00155
00156 void Graphical_UI::resetCmd() {
00157 Q_EMIT reset();
00158 if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->reset();
00159 QString message = tr("Graph Reset");
00160 statusBar()->showMessage(message);
00161 infoLabel->setText("A fresh new graph is waiting");
00162 }
00163
00164 void Graphical_UI::setStatus(QString message){
00165 statusBar()->showMessage(message);
00166 }
00167 void Graphical_UI::setInfo2(QString message){
00168 infoLabel2->setText(message);
00169 infoLabel2->repaint();
00170 }
00171 void Graphical_UI::setInfo(QString message){
00172 infoLabel->setText(message);
00173 infoLabel->repaint();
00174 }
00175
00176 void Graphical_UI::quickSaveAll() {
00177 Q_EMIT saveAllClouds(filename);
00178 QString message = tr("Saving Whole Model to ");
00179 message.append(QDir::currentPath());
00180 message.append(filename);
00181 statusBar()->showMessage(message);
00182
00183 }
00184
00185 void Graphical_UI::saveFeatures() {
00186 filename = QFileDialog::getSaveFileName(this, "Save Features to File", filename, tr("YAML (*.yml);;XML (*.xml)"));
00187 Q_EMIT saveAllFeatures(filename);
00188 QString message = tr("Saving Features");
00189 statusBar()->showMessage(message);
00190 }
00191
00192 void Graphical_UI::saveAll() {
00193 filename = QFileDialog::getSaveFileName(this, "Save Point CLoud to File", filename, tr("PCD (*.pcd);;PLY (*ply)"));
00194 Q_EMIT saveAllClouds(filename);
00195 QString message = tr("Saving Whole Model");
00196 statusBar()->showMessage(message);
00197
00198 }
00199 void Graphical_UI::showEdgeErrors() {
00200 QString myfilename = QFileDialog::getSaveFileName(this, "Save Current Trajectory Estimate", "trajectory", tr("All Files (*.*)"));
00201 Q_EMIT printEdgeErrors(myfilename);
00202 QString message = tr("Triggering Edge Printing");
00203 statusBar()->showMessage(message);
00204 }
00205 void Graphical_UI::optimizeGraphTrig() {
00206 Q_EMIT optimizeGraph();
00207 QString message = tr("Triggering Optimizer");
00208 statusBar()->showMessage(message);
00209 }
00210 void Graphical_UI::saveVectorGraphic() {
00211 QMessageBox::warning(this, tr("Don't render to pdf while point clouds are shown"), tr("This is meant for rendereing the pose graph. Rendering clouds to pdf will generate huge files!"));
00212 QString myfilename = QFileDialog::getSaveFileName(this, "Save Current 3D Display to Vector Graphic", "pose_graph.pdf", tr("All Files (*.*)"));
00213 glviewer->drawToPS(myfilename);
00214 QString message = tr("Drawing current Display");
00215 statusBar()->showMessage(message);
00216 }
00217 void Graphical_UI::saveTrajectoryDialog() {
00218 QString myfilename = QFileDialog::getSaveFileName(this, "Save Current Trajectory Estimate", "trajectory", tr("All Files (*.*)"));
00219 Q_EMIT saveTrajectory(myfilename);
00220 QString message = tr("Saving current trajectory estimate (and possibly ground truth).");
00221 statusBar()->showMessage(message);
00222 }
00223 void Graphical_UI::saveIndividual() {
00224 QString tmpfilename(filename);
00225 tmpfilename.remove(".pcd", Qt::CaseInsensitive);
00226 tmpfilename.remove(".ply", Qt::CaseInsensitive);
00227 filename = QFileDialog::getSaveFileName(this, "Save point cloud to one file per node", tmpfilename, tr("PCD (*.pcd)"));
00228 Q_EMIT saveIndividualClouds(filename);
00229 QString message = tr("Saving Model Node-Wise");
00230 statusBar()->showMessage(message);
00231
00232 }
00233
00234 void Graphical_UI::sendAll() {
00235 Q_EMIT sendAllClouds();
00236 QString message = tr("Sending Whole Model");
00237 statusBar()->showMessage(message);
00238
00239 }
00240
00241 void Graphical_UI::setRotationGrid() {
00242 bool ok;
00243 double value = QInputDialog::getDouble(this, tr("Set Rotation Stepping in Degree"),
00244 tr("Enter Stepping:"), 1.00, -10000000, 10000000, 2, &ok);
00245 if(ok){ glviewer->setRotationGrid(value); }
00246 }
00247 void Graphical_UI::setStereoShift() {
00248 bool ok;
00249 double value = QInputDialog::getDouble(this, tr("Set Stereo Camera shift"),
00250 tr("Enter Shift:"), 0.10, -10000000, 10000000, 2, &ok);
00251 if(ok){ glviewer->setStereoShift(value); }
00252 }
00253
00254 void Graphical_UI::setMax() {
00255 bool ok;
00256 double value = QInputDialog::getDouble(this, tr("Set Max Depth"),
00257 tr("Enter Max Depth [in cm]\n (negativ if no Filtering is required):"), -100.00, -10000000, 10000000, 2, &ok);
00258 if(ok){
00259 Q_EMIT setMaxDepth(value/100.0);
00260 }
00261 }
00262 void Graphical_UI::toggleFullscreen(bool mode){
00263 this->menuBar()->setVisible(!mode);
00264 this->gridlayout->setMargin(mode?0:5);
00265 this->statusBar()->setVisible(!mode);
00266 if(mode){
00267 this->showFullScreen();
00268 } else {
00269 this->showNormal();
00270 }
00271 }
00272 void Graphical_UI::pruneEdgesWithHighError(){
00273 bool ok;
00274 float value = QInputDialog::getDouble(this, tr("Set Max Edge Error"),
00275 tr("No Text"), 1.00, -10000000, 10000000, 2, &ok);
00276 if(ok){
00277 Q_EMIT pruneEdgesWithErrorAbove(value);
00278 }
00279 }
00280 void Graphical_UI::sendFinished() {
00281
00282 QString message = tr("Finished Sending");
00283 statusBar()->showMessage(message);
00284
00285 }
00286
00287 void Graphical_UI::getOneFrameCmd() {
00288 Q_EMIT getOneFrame();
00289 QString message = tr("Getting a single frame");
00290 statusBar()->showMessage(message);
00291
00292 }
00293 void Graphical_UI::deleteLastFrameCmd() {
00294 Q_EMIT deleteLastFrame();
00295 QString message = tr("Deleting the last node from the graph");
00296 statusBar()->showMessage(message);
00297
00298 }
00299
00300 void Graphical_UI::toggleMappingPriv(bool mapping_on) {
00301 Q_EMIT toggleMapping(mapping_on);
00302 }
00303
00304 void Graphical_UI::bagRecording(bool pause_on) {
00305 Q_EMIT toggleBagRecording();
00306 if(pause_on) {
00307 QString message = tr("Recording Bagfile.");
00308 statusBar()->showMessage(message);
00309
00310 } else {
00311 QString message = tr("Stopped Recording.");
00312 statusBar()->showMessage(message);
00313
00314 }
00315 }
00316 void Graphical_UI::toggleCloudStorage(bool storage) {
00317 ParameterServer::instance()->set("store_pointclouds", storage);
00318 }
00319
00320 void Graphical_UI::pause(bool pause_on) {
00321 Q_EMIT togglePause();
00322 if(pause_on) {
00323 QString message = tr("Processing.");
00324 statusBar()->showMessage(message);
00325
00326 } else {
00327 QString message = tr("Stopped processing.");
00328 statusBar()->showMessage(message);
00329
00330 }
00331 }
00332
00333 void Graphical_UI::help() {
00334 QMessageBox::about(this, tr("Help Menu"), *mouseHelpText );
00335 }
00336 void Graphical_UI::about() {
00337 QMessageBox::about(this, tr("About RGBDSLAM"), *infoText + *licenseText);
00338 }
00339
00340 void Graphical_UI::set2DStream(bool is_on) {
00341 if(is_on){
00342 visual_image_label->show();
00343 depth_image_label->show();
00344 feature_flow_image_label->show();
00345 QList<int> list;
00346 list.append(1);
00347 list.append(1);
00348 vsplitter->setSizes(list);
00349 } else {
00350 visual_image_label->hide();
00351 depth_image_label->hide();
00352 feature_flow_image_label->hide();
00353 QList<int> list;
00354 list.append(1);
00355 list.append(0);
00356 vsplitter->setSizes(list);
00357 }
00358 }
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369 void Graphical_UI::createMenus() {
00370
00371 QMenu *graphMenu;
00372 QMenu *actionMenu;
00373 QMenu *viewMenu;
00374 QMenu *settingsMenu;
00375 QMenu *helpMenu;
00376
00377
00378 graphMenu = menuBar()->addMenu(tr("&Graph"));
00379
00380 QAction *quickSaveAct = new QAction(tr("&Save"), this);
00381 quickSaveAct->setShortcuts(QKeySequence::Save);
00382 quickSaveAct->setStatusTip(tr("Save all stored point clouds with common coordinate frame to a pcd file"));
00383 quickSaveAct->setIcon(QIcon::fromTheme("document-save"));
00384 connect(quickSaveAct, SIGNAL(triggered()), this, SLOT(quickSaveAll()));
00385 graphMenu->addAction(quickSaveAct);
00386 this->addAction(quickSaveAct);
00387
00388 QAction *saveFeaturesAct = new QAction(tr("Save &Features"), this);
00389 saveFeaturesAct->setShortcut(QString("Ctrl+F"));
00390 saveFeaturesAct->setStatusTip(tr("Save all feature positions and descriptions in a common coordinate frame to a yaml or xml file"));
00391 saveFeaturesAct->setIcon(QIcon::fromTheme("document-save"));
00392 connect(saveFeaturesAct, SIGNAL(triggered()), this, SLOT(saveFeatures()));
00393 graphMenu->addAction(saveFeaturesAct);
00394 this->addAction(saveFeaturesAct);
00395
00396 QAction *saveAct = new QAction(tr("&Save as..."), this);
00397 saveAct->setShortcuts(QKeySequence::SaveAs);
00398 saveAct->setStatusTip(tr("Save all stored point clouds with common coordinate frame"));
00399 saveAct->setIcon(QIcon::fromTheme("document-save-as"));
00400 connect(saveAct, SIGNAL(triggered()), this, SLOT(saveAll()));
00401 graphMenu->addAction(saveAct);
00402 this->addAction(saveAct);
00403
00404 QAction *saveIndiAct = new QAction(tr("&Save Node-Wise..."), this);
00405 saveIndiAct->setShortcut(QString("Ctrl+N"));
00406 saveIndiAct->setStatusTip(tr("Save stored point clouds in individual files"));
00407 saveAct->setIcon(QIcon::fromTheme("document-save-all"));
00408 connect(saveIndiAct, SIGNAL(triggered()), this, SLOT(saveIndividual()));
00409 graphMenu->addAction(saveIndiAct);
00410 this->addAction(saveIndiAct);
00411
00412 QAction *sendAct = new QAction(tr("&Send Model"), this);
00413 sendAct->setShortcut(QString("Ctrl+M"));
00414 sendAct->setStatusTip(tr("Send out all stored point clouds with corrected transform"));
00415 sendAct->setIcon(QIcon::fromTheme("document-send"));
00416 connect(sendAct, SIGNAL(triggered()), this, SLOT(sendAll()));
00417 graphMenu->addAction(sendAct);
00418 this->addAction(sendAct);
00419
00420 graphMenu->addSeparator();
00421
00422 QAction *toggleMappingAct = new QAction(tr("Toggle &Mapping"), this);
00423 toggleMappingAct->setShortcut(QString("M"));
00424 toggleMappingAct->setCheckable(true);
00425 toggleMappingAct->setChecked(true);
00426 toggleMappingAct->setStatusTip(tr("Toggle between SLAM and Localization"));
00427 toggleMappingAct->setIcon(QIcon::fromTheme("media-playback-start"));
00428 connect(toggleMappingAct, SIGNAL(toggled(bool)), this, SLOT(toggleMappingPriv(bool)));
00429 graphMenu->addAction(toggleMappingAct);
00430 this->addAction(toggleMappingAct);
00431
00432 graphMenu->addSeparator();
00433
00434 QAction *optimizeAct = new QAction(tr("Optimize Trajectory &Estimate"), this);
00435 optimizeAct->setShortcut(QString("O"));
00436 optimizeAct->setStatusTip(tr("Compute optimized pose graph with g2o"));
00437 connect(optimizeAct, SIGNAL(triggered()), this, SLOT(optimizeGraphTrig()));
00438 graphMenu->addAction(optimizeAct);
00439 this->addAction(optimizeAct);
00440
00441 graphMenu->addSeparator();
00442
00443 QAction *exitAct = new QAction(tr("E&xit"), this);
00444 exitAct->setShortcuts(QKeySequence::Quit);
00445 exitAct->setStatusTip(tr("Exit the application"));
00446 exitAct->setIcon(QIcon::fromTheme("application-exit"));
00447 connect(exitAct, SIGNAL(triggered()), this, SLOT(close()));
00448 graphMenu->addAction(exitAct);
00449 this->addAction(exitAct);
00450
00451
00452
00453 actionMenu = menuBar()->addMenu(tr("&Processing"));
00454
00455 QAction *newAct;
00456 newAct = new QAction(tr("&Reset"), this);
00457 newAct->setShortcut(QString("Ctrl+R"));
00458 newAct->setStatusTip(tr("Reset the graph, clear all data collected"));
00459 newAct->setIcon(QIcon::fromTheme("edit-delete"));
00460 connect(newAct, SIGNAL(triggered()), this, SLOT(resetCmd()));
00461 actionMenu->addAction(newAct);
00462 this->addAction(newAct);
00463
00464 QAction *pauseAct = new QAction(tr("&Process"), this);
00465 pauseAct->setShortcut(QString(" "));
00466 pauseAct->setCheckable(true);
00467 pauseAct->setChecked(!ParameterServer::instance()->get<bool>("start_paused"));
00468 pauseAct->setStatusTip(tr("Start/stop processing of frames"));
00469 pauseAct->setIcon(QIcon::fromTheme("media-playback-start"));
00470 connect(pauseAct, SIGNAL(toggled(bool)), this, SLOT(pause(bool)));
00471 actionMenu->addAction(pauseAct);
00472 this->addAction(pauseAct);
00473
00474 QAction *oneFrameAct = new QAction(tr("Capture One& Frame"), this);
00475 oneFrameAct->setShortcuts(QKeySequence::InsertParagraphSeparator);
00476 oneFrameAct->setStatusTip(tr("Process one frame only"));
00477 connect(oneFrameAct, SIGNAL(triggered()), this, SLOT(getOneFrameCmd()));
00478 actionMenu->addAction(oneFrameAct);
00479 this->addAction(oneFrameAct);
00480
00481 QAction *delFrameAct = new QAction(tr("&Delete Last Node"), this);
00482 delFrameAct->setShortcut(QString("Backspace"));
00483 delFrameAct->setStatusTip(tr("Remove last node from graph"));
00484 delFrameAct->setIcon(QIcon::fromTheme("edit-undo"));
00485 connect(delFrameAct, SIGNAL(triggered()), this, SLOT(deleteLastFrameCmd()));
00486 actionMenu->addAction(delFrameAct);
00487 this->addAction(delFrameAct);
00488
00489 QAction *bagRecordingAct = new QAction(tr("&Bagfile Recording"), this);
00490 bagRecordingAct->setShortcut(QString("R"));
00491 bagRecordingAct->setCheckable(true);
00492 bagRecordingAct->setChecked(false);
00493 bagRecordingAct->setStatusTip(tr("Start/stop recording of frames to bagfile"));
00494 bagRecordingAct->setIcon(QIcon::fromTheme("media-record"));
00495 connect(bagRecordingAct, SIGNAL(toggled(bool)), this, SLOT(bagRecording(bool)));
00496 actionMenu->addAction(bagRecordingAct);
00497 this->addAction(bagRecordingAct);
00498
00499 QAction *compareAct = new QAction(tr("Save Trajectory &Estimate"), this);
00500 compareAct->setShortcut(QString("Ctrl+E"));
00501 compareAct->setStatusTip(tr("Save trajectory estimate (and ground truth trajectory if available) for external evaluation."));
00502 connect(compareAct, SIGNAL(triggered()), this, SLOT(saveTrajectoryDialog()));
00503 actionMenu->addAction(compareAct);
00504 this->addAction(compareAct);
00505
00506
00507
00508
00509
00510
00511
00512
00513
00514
00515
00516 QAction *maxAct = new QAction(tr("Set Maximum &Depth"), this);
00517 maxAct->setShortcut(QString("Ctrl+D"));
00518 maxAct->setStatusTip(tr("Set the Maximum Depth a Point can have (negativ if no Filtering is required)"));
00519 connect(maxAct, SIGNAL(triggered()), this, SLOT(setMax()));
00520 actionMenu->addAction(maxAct);
00521 this->addAction(maxAct);
00522
00523 QAction *pruneAct = new QAction(tr("Set Ma&ximum Edge Error"), this);
00524 pruneAct->setShortcut(QString("Ctrl+X"));
00525 pruneAct->setStatusTip(tr("Set the Maximum Allowed for Edges"));
00526 connect(pruneAct, SIGNAL(triggered()), this, SLOT(pruneEdgesWithHighError()));
00527 actionMenu->addAction(pruneAct);
00528 this->addAction(pruneAct);
00529
00530 QAction *psOutputAct = new QAction(tr("&Write PDF File"), this);
00531 psOutputAct->setShortcut(QString("W"));
00532 psOutputAct->setStatusTip(tr("Write 3D Scene to a PDF File. Warning: Meant for Pose Graphs not for the clouds"));
00533 psOutputAct->setIcon(QIcon::fromTheme("application-pdf"));
00534 connect(psOutputAct, SIGNAL(triggered()), this, SLOT(saveVectorGraphic()));
00535 actionMenu->addAction(psOutputAct);
00536 this->addAction(psOutputAct);
00537
00538 QAction *toggleCloudStorageAct = new QAction(tr("&Store Point Clouds"), this);
00539 QList<QKeySequence> tcs_shortcuts;
00540 tcs_shortcuts.append(QString("Ctrl+P"));
00541 toggleCloudStorageAct->setShortcuts(tcs_shortcuts);
00542 toggleCloudStorageAct->setCheckable(true);
00543 toggleCloudStorageAct->setChecked(ParameterServer::instance()->get<bool>("store_pointclouds"));
00544 toggleCloudStorageAct->setStatusTip(tr("Toggle storing of point clouds (for later sending, map creation)"));
00545 toggleCloudStorageAct->setIcon(QIcon::fromTheme("server-database"));
00546 connect(toggleCloudStorageAct, SIGNAL(toggled(bool)), this, SLOT(toggleCloudStorage(bool)));
00547 actionMenu->addAction(toggleCloudStorageAct);
00548 this->addAction(toggleCloudStorageAct);
00549
00550
00551
00552 viewMenu = menuBar()->addMenu(tr("&View"));
00553
00554
00555 QAction *toggleFullscreenAct = new QAction(tr("&Fullscreen"), this);
00556 QList<QKeySequence> shortcuts;
00557 shortcuts.append(QString("F"));
00558 toggleFullscreenAct->setShortcuts(shortcuts);
00559 toggleFullscreenAct->setCheckable(true);
00560 toggleFullscreenAct->setChecked(false);
00561 toggleFullscreenAct->setStatusTip(tr("Toggle Fullscreen"));
00562 toggleFullscreenAct->setIcon(QIcon::fromTheme("view-fullscreen"));
00563 connect(toggleFullscreenAct, SIGNAL(toggled(bool)), this, SLOT(toggleFullscreen(bool)));
00564 viewMenu->addAction(toggleFullscreenAct);
00565 this->addAction(toggleFullscreenAct);
00566
00567 QAction *toggleStreamAct = new QAction(tr("Toggle &2D Stream"), this);
00568 toggleStreamAct->setShortcut(QString("2"));
00569 toggleStreamAct->setCheckable(true);
00570 toggleStreamAct->setChecked(true);
00571 toggleStreamAct->setStatusTip(tr("Turn off the Image Stream"));
00572 connect(toggleStreamAct, SIGNAL(toggled(bool)), this, SLOT(set2DStream(bool)));
00573 viewMenu->addAction(toggleStreamAct);
00574 this->addAction(toggleStreamAct);
00575
00576 if(ParameterServer::instance()->get<bool>("use_glwidget"))
00577 {
00578 QAction *toggleGLViewerAct = new QAction(tr("Toggle &3D Display"), this);
00579 toggleGLViewerAct->setShortcut(QString("3"));
00580 toggleGLViewerAct->setCheckable(true);
00581 toggleGLViewerAct->setChecked(true);
00582 toggleGLViewerAct->setStatusTip(tr("Turn off the OpenGL Display"));
00583 connect(toggleGLViewerAct, SIGNAL(toggled(bool)), glviewer, SLOT(setVisible(bool)));
00584 viewMenu->addAction(toggleGLViewerAct);
00585 this->addAction(toggleGLViewerAct);
00586
00587 QAction *toggleTriangulationAct = new QAction(tr("&Toggle Triangulation"), this);
00588 toggleTriangulationAct->setShortcut(QString("T"));
00589 toggleTriangulationAct->setStatusTip(tr("Switch between surface, wireframe and point cloud"));
00590 connect(toggleTriangulationAct, SIGNAL(triggered(bool)), glviewer, SLOT(toggleTriangulation()));
00591 viewMenu->addAction(toggleTriangulationAct);
00592 this->addAction(toggleTriangulationAct);
00593
00594 QAction *toggleFollowAct = new QAction(tr("Follow &Camera"), this);
00595 toggleFollowAct->setShortcut(QString("Shift+F"));
00596 toggleFollowAct->setCheckable(true);
00597 toggleFollowAct->setChecked(true);
00598 toggleFollowAct->setStatusTip(tr("Always use viewpoint of last frame (except zoom)"));
00599 connect(toggleFollowAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleFollowMode(bool)));
00600 viewMenu->addAction(toggleFollowAct);
00601 this->addAction(toggleFollowAct);
00602
00603 QAction *toggleShowIDsAct = new QAction(tr("Show Pose IDs"), this);
00604 toggleShowIDsAct->setShortcut(QString("I"));
00605 toggleShowIDsAct->setCheckable(true);
00606 toggleShowIDsAct->setChecked(false);
00607 toggleShowIDsAct->setStatusTip(tr("Display pose ids at axes"));
00608 connect(toggleShowIDsAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleShowIDs(bool)));
00609 viewMenu->addAction(toggleShowIDsAct);
00610 this->addAction(toggleShowIDsAct);
00611
00612 QAction *toggleShowPosesAct = new QAction(tr("Show &Poses of Graph"), this);
00613 toggleShowPosesAct->setShortcut(QString("P"));
00614 toggleShowPosesAct->setCheckable(true);
00615 toggleShowPosesAct->setChecked(ParameterServer::instance()->get<bool>("show_axis"));
00616 toggleShowPosesAct->setStatusTip(tr("Display poses as axes"));
00617 connect(toggleShowPosesAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleShowPoses(bool)));
00618 viewMenu->addAction(toggleShowPosesAct);
00619 this->addAction(toggleShowPosesAct);
00620
00621 QAction *toggleShowEdgesAct = new QAction(tr("Show &Edges of Graph"), this);
00622 toggleShowEdgesAct->setShortcut(QString("E"));
00623 toggleShowEdgesAct->setCheckable(true);
00624 toggleShowEdgesAct->setChecked(ParameterServer::instance()->get<bool>("show_axis"));
00625 toggleShowEdgesAct->setStatusTip(tr("Display edges of pose graph as lines"));
00626 connect(toggleShowEdgesAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleShowEdges(bool)));
00627 viewMenu->addAction(toggleShowEdgesAct);
00628 this->addAction(toggleShowEdgesAct);
00629
00630 QAction *toggleStereoAct = new QAction(tr("Stere&o View"), this);
00631 toggleStereoAct->setShortcut(QString("Ctrl+Shift+O"));
00632 toggleStereoAct->setCheckable(true);
00633 toggleStereoAct->setChecked(false);
00634 toggleStereoAct->setStatusTip(tr("Split screen view with slightly shifted Camera"));
00635 connect(toggleStereoAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleStereo(bool)));
00636 viewMenu->addAction(toggleStereoAct);
00637 this->addAction(toggleStereoAct);
00638
00639 QAction *toggleCloudDisplay = new QAction(tr("Show &Clouds"), this);
00640 toggleCloudDisplay->setShortcut(QString("C"));
00641 toggleCloudDisplay->setCheckable(true);
00642 toggleCloudDisplay->setChecked(true);
00643 toggleCloudDisplay->setStatusTip(tr("Toggle whether point clouds should be rendered"));
00644 connect(toggleCloudDisplay, SIGNAL(toggled(bool)), glviewer, SLOT(toggleShowClouds(bool)));
00645 viewMenu->addAction(toggleCloudDisplay);
00646 this->addAction(toggleCloudDisplay);
00647
00648 QAction *toggleBGColor = new QAction(tr("Toggle Background"), this);
00649 toggleBGColor->setShortcut(QString("B"));
00650 toggleBGColor->setCheckable(true);
00651 toggleBGColor->setChecked(true);
00652 toggleBGColor->setStatusTip(tr("Toggle whether background should be white or black"));
00653 connect(toggleBGColor, SIGNAL(toggled(bool)), glviewer, SLOT(toggleBackgroundColor(bool)));
00654 viewMenu->addAction(toggleBGColor);
00655 this->addAction(toggleBGColor);
00656
00657 QAction *setRotationGridAct = new QAction(tr("Set Rotation &Grid"), this);
00658 setRotationGridAct->setShortcut(QString("G"));
00659 setRotationGridAct->setStatusTip(tr("Discretize Rotation in Viewer"));
00660 connect(setRotationGridAct, SIGNAL(triggered()), this, SLOT(setRotationGrid()));
00661 viewMenu->addAction(setRotationGridAct);
00662 this->addAction(setRotationGridAct);
00663
00664 QAction *setShiftAct = new QAction(tr("Set Stereo Offset"), this);
00665 setShiftAct->setShortcut(QString("<"));
00666 setShiftAct->setStatusTip(tr("Set the distance between the virtual cameras for stereo view"));
00667 connect(setShiftAct, SIGNAL(triggered()), this, SLOT(setStereoShift()));
00668 viewMenu->addAction(setShiftAct);
00669 this->addAction(setShiftAct);
00670
00671 }
00672
00673
00674
00675 settingsMenu = menuBar()->addMenu(tr("&Settings"));
00676
00677 QAction *reloadAct;
00678 reloadAct = new QAction(tr("&Reload Config"), this);
00679 reloadAct->setStatusTip(tr("Reload Configuration from Parameter Server."));
00680 reloadAct->setIcon(QIcon::fromTheme("reload"));
00681 connect(reloadAct, SIGNAL(triggered()), this, SLOT(reloadConfig()));
00682 settingsMenu->addAction(reloadAct);
00683 this->addAction(reloadAct);
00684
00685 QAction *optionAct = new QAction(tr("&View Current Settings"), this);
00686 optionAct->setShortcut(QString("?"));
00687 optionAct->setStatusTip(tr("Display the currently active options"));
00688 connect(optionAct, SIGNAL(triggered()), this, SLOT(showOptions()));
00689 settingsMenu->addAction(optionAct);
00690 this->addAction(optionAct);
00691
00692
00693 helpMenu = menuBar()->addMenu(tr("&Help"));
00694
00695 QAction *helpAct = new QAction(tr("&Usage Help"), this);
00696 helpAct->setShortcuts(QKeySequence::HelpContents);
00697 helpAct->setStatusTip(tr("Show usage information"));
00698 helpAct->setIcon(QIcon::fromTheme("help-contents"));
00699 connect(helpAct, SIGNAL(triggered()), this, SLOT(help()));
00700 helpMenu->addAction(helpAct);
00701 this->addAction(helpAct);
00702
00703 QAction *aboutAct = new QAction(tr("&About RGBDSLAM"), this);
00704 aboutAct->setShortcut(QString("Ctrl+A"));
00705 aboutAct->setStatusTip(tr("Show information about RGBDSLAM"));
00706 aboutAct->setIcon(QIcon::fromTheme("help-about"));
00707 connect(aboutAct, SIGNAL(triggered()), this, SLOT(about()));
00708 helpMenu->addAction(aboutAct);
00709 this->addAction(aboutAct);
00710
00711 }
00712
00713 GLViewer* Graphical_UI::getGLViewer() {
00714 return glviewer;
00715 }
00716
00717 void Graphical_UI::showOptions(){
00718 QScrollArea* scrollarea = new QScrollArea();
00719 QWidget* scrollarea_content = new QWidget(scrollarea);
00720 scrollarea_content->setMinimumWidth(500);
00721 QFormLayout *formLayout = new QFormLayout(scrollarea_content);
00722 formLayout->setFieldGrowthPolicy(QFormLayout::AllNonFixedFieldsGrow);
00723 formLayout->setLabelAlignment(Qt::AlignLeft);
00724 formLayout->setVerticalSpacing(10);
00725
00726 QLabel* intro = new QLabel("This is an read-only view of the current settings. To modify RGBDSLAM's settings use the ROS parameter server functionality (i.e. set options either in a launch-file or as a command line parameter).");
00727 intro->setWordWrap(true);
00728 formLayout->addRow(intro);
00729
00730
00731 std::map<std::string, boost::any>& config = ParameterServer::instance()->getConfigData();
00732 std::map<std::string, boost::any>::const_iterator itr;
00733 for (itr = config.begin(); itr != config.end(); ++itr) {
00734 QString name(itr->first.c_str());
00735 QString description(ParameterServer::instance()->getDescription(itr->first).c_str());
00736 QLabel* desc = new QLabel("<b>"+name+"</b><br/>"+description+"<br/><br/>");
00737 desc->setWordWrap(true);
00738 desc->setToolTip(description);
00739
00740 if (itr->second.type() == typeid(std::string)) {
00741 QLineEdit* editbox = new QLineEdit(QString(boost::any_cast<std::string>(itr->second).c_str()), scrollarea_content);
00742 editbox->setToolTip(description);
00743 editbox->setReadOnly(true);
00744 formLayout->addRow(desc, editbox);
00745 } else if (itr->second.type() == typeid(int)) {
00746 QSpinBox* isbox = new QSpinBox();
00747 isbox->setMaximum(1e9);
00748 isbox->setValue(boost::any_cast<int>(itr->second));
00749 isbox->setToolTip(description);
00750 isbox->setReadOnly(true);
00751 formLayout->addRow(desc, isbox);
00752 } else if (itr->second.type() == typeid(double)) {
00753 QDoubleSpinBox* dsbox = new QDoubleSpinBox();
00754 dsbox->setMaximum(1e9);
00755 dsbox->setValue(boost::any_cast<double>(itr->second));
00756 dsbox->setToolTip(description);
00757 dsbox->setReadOnly(true);
00758 formLayout->addRow(desc, dsbox);
00759 } else if (itr->second.type() == typeid(bool)) {
00760 QCheckBox* checkbox = new QCheckBox("", scrollarea_content);
00761 checkbox->setChecked(boost::any_cast<bool>(itr->second));
00762 checkbox->setToolTip(description);
00763 formLayout->addRow(desc, checkbox);
00764 }
00765 }
00766 scrollarea_content->setLayout(formLayout);
00767 scrollarea->setWidget(scrollarea_content);
00768 scrollarea->setMinimumWidth(560);
00769 scrollarea->show();
00770 scrollarea->raise();
00771 scrollarea->activateWindow();
00772 }
00773