root / rgbdslam / src / qt_gui.cpp @ 9240aaa3
History | View | Annotate | Download (22.1 KB)
1 | 9240aaa3 | Alex | /* This file is part of RGBDSLAM.
|
---|---|---|---|
2 | *
|
||
3 | * RGBDSLAM is free software: you can redistribute it and/or modify
|
||
4 | * it under the terms of the GNU General Public License as published by
|
||
5 | * the Free Software Foundation, either version 3 of the License, or
|
||
6 | * (at your option) any later version.
|
||
7 | *
|
||
8 | * RGBDSLAM is distributed in the hope that it will be useful,
|
||
9 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||
10 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||
11 | * GNU General Public License for more details.
|
||
12 | *
|
||
13 | * You should have received a copy of the GNU General Public License
|
||
14 | * along with RGBDSLAM. If not, see <http://www.gnu.org/licenses/>.
|
||
15 | */
|
||
16 | |||
17 | |||
18 | /* This is the main widget of the application.
|
||
19 | * It sets up some not yet useful menus and
|
||
20 | * three qlabels in the layout of the central widget
|
||
21 | * that can be used to show qimages via the slots
|
||
22 | * setDepthImage and setVisualImage.
|
||
23 | */
|
||
24 | #include <QtGui> |
||
25 | #include <QPixmap> |
||
26 | #include <QFont> |
||
27 | #include <QIcon> |
||
28 | #include <QKeySequence> |
||
29 | #include "qt_gui.h" |
||
30 | #include <limits> |
||
31 | |||
32 | ///Constructs a QT GUI for easy control of RGBDSLAM
|
||
33 | Graphical_UI::Graphical_UI() : filename("quicksave.pcd"), glviewer(NULL) |
||
34 | { |
||
35 | QWidget *widget = new QWidget;
|
||
36 | setCentralWidget(widget); |
||
37 | |||
38 | //QWidget *topFiller = new QWidget;
|
||
39 | //topFiller->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||
40 | infoText = new QString(tr(
|
||
41 | "<p><b>RGBDSLAM</b> uses visual features to identify corresponding 3D locations "
|
||
42 | "in RGBD data. The correspondences are used to reconstruct the camera motion. "
|
||
43 | "The SLAM-backend HOG-MAN is used to integrate the transformations between"
|
||
44 | "the RGBD-images and compute a globally consistent 6D trajectory.</p>"
|
||
45 | "<p></p>"));
|
||
46 | licenseText = new QString(tr(
|
||
47 | "<p>RGBDSLAM is free software: you can redistribute it and/or modify"
|
||
48 | "it under the terms of the GNU General Public License as published by"
|
||
49 | "the Free Software Foundation, either version 3 of the License, or"
|
||
50 | "(at your option) any later version.</p>"
|
||
51 | "<p>RGBDSLAM is distributed in the hope that it will be useful,"
|
||
52 | "but WITHOUT ANY WARRANTY; without even the implied warranty of"
|
||
53 | "MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the"
|
||
54 | "GNU General Public License for more details.</p>"
|
||
55 | "<p>You should have received a copy of the GNU General Public License"
|
||
56 | "along with RGBDSLAM. If not, refer to <a href=\"http://www.gnu.org/licenses/\">http://www.gnu.org/licenses</a>.</p>"));
|
||
57 | /*menuHelpText = new QString(tr(
|
||
58 | "<p><b>Menu Commands:</b>"
|
||
59 | "<ul><li><b>Graph</b></li><ul>"
|
||
60 | "<li><i>Save Model</i> saves the aggregated cloud to file.</li>"
|
||
61 | "<li><i>Save Model</i> saves the aggregated cloud to file.</li>"
|
||
62 | "<li><i>Send Model</i> sends the clouds and their transforms via ROS.</li>"
|
||
63 | "</ul><li><b>Processing</b></li><ul>"
|
||
64 | "<li><i>Process</i> toggles the processing.</li>"
|
||
65 | "<li><i>Reset</i> to clear the collected information.</li>"
|
||
66 | "<li><i>Capture One Frame</i> to Process one camera image.</li>"
|
||
67 | "<li><i>Delete Last Node</i> to clear the information about the last processed image.</li>"
|
||
68 | "</ul><li><b>Information</b></li><ul>"
|
||
69 | "<li><i>Current Transformation Matrix</i> displays the transformation from the first to the last node.</li>"
|
||
70 | "<li><i>About RGBDSLAM</i> displays information about this software.</li>"
|
||
71 | "<li><i>Usage Help</i> displays this text</li></ul></ul><p>"));*/
|
||
72 | mouseHelpText = new QString(tr(
|
||
73 | "<p><b>3D Viewer Mouse Commands:</b>"
|
||
74 | "<ul><li><i>Left/Right button:</i> rotation.</li>"
|
||
75 | " <li><i>Middle button:</i> shift.</li>"
|
||
76 | " <li><i>Wheel:</i> zoom.</li>"
|
||
77 | " <li><i>Double click on object:</i> set pivot to clicked point.</li>"
|
||
78 | " <li><i>Double click on background:</i> reset view to camera pose.</li><ul></p>")); feature_flow_image_label = new QLabel(*mouseHelpText); |
||
79 | feature_flow_image_label->setWordWrap(true);
|
||
80 | feature_flow_image_label->setMargin(10);
|
||
81 | feature_flow_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken); |
||
82 | visual_image_label = new QLabel("<i>Waiting for monochrome image...</i>"); |
||
83 | visual_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken); |
||
84 | visual_image_label->setAlignment(Qt::AlignCenter); |
||
85 | //visual_image_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||
86 | depth_image_label = new QLabel(tr("<i>Waiting for depth image...</i>")); |
||
87 | depth_image_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken); |
||
88 | depth_image_label->setAlignment(Qt::AlignCenter); |
||
89 | //depth_image_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||
90 | //transform_label = new QLabel(tr("<i>Waiting for transformation matrix...</i>"));
|
||
91 | //transform_label->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken);
|
||
92 | //transform_label->setAlignment(Qt::AlignCenter);
|
||
93 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer = new GLViewer(this);//displays the cloud in 3d |
||
94 | |||
95 | //QFont typewriter_font;
|
||
96 | //typewriter_font.setStyleHint(QFont::TypeWriter);
|
||
97 | //transform_label->setFont(typewriter_font);
|
||
98 | |||
99 | //QWidget *bottomFiller = new QWidget;
|
||
100 | //bottomFiller->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
|
||
101 | |||
102 | gridlayout = new QGridLayout;
|
||
103 | gridlayout->setMargin(5);
|
||
104 | //gridlayout->addWidget(infoLabel, 0,0);
|
||
105 | //gridlayout->addWidget(transform_label, 0,0,1,0); //with rowspan
|
||
106 | //gridlayout->addWidget(transform_label, 0,0);
|
||
107 | if(ParameterServer::instance()->get<bool>("use_glwidget")) gridlayout->addWidget(glviewer, 0,0,1,0); |
||
108 | gridlayout->addWidget(visual_image_label, 1,0); |
||
109 | gridlayout->addWidget(depth_image_label, 1,1); |
||
110 | gridlayout->addWidget(feature_flow_image_label, 1,2); |
||
111 | widget->setLayout(gridlayout); |
||
112 | |||
113 | createMenus(); |
||
114 | |||
115 | tmpLabel = new QLabel();
|
||
116 | statusBar()->insertWidget(0,tmpLabel, 0); |
||
117 | QString message = tr("Ready for RGBDSLAM");
|
||
118 | statusBar()->showMessage(message); |
||
119 | |||
120 | infoLabel2 = new QLabel(tr("Waiting for motion information...")); |
||
121 | infoLabel2->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken); |
||
122 | infoLabel2->setAlignment(Qt::AlignRight); |
||
123 | statusBar()->addPermanentWidget(infoLabel2, 0);
|
||
124 | |||
125 | infoLabel = new QLabel(tr("<i>Press Enter or Space to Start</i>")); |
||
126 | infoLabel->setFrameStyle(QFrame::StyledPanel | QFrame::Sunken); |
||
127 | infoLabel->setAlignment(Qt::AlignRight); |
||
128 | statusBar()->addPermanentWidget(infoLabel, 0);
|
||
129 | |||
130 | setWindowTitle(tr("RGBDSLAM"));
|
||
131 | setMinimumSize(790, 590); |
||
132 | //resize(1024, 800);
|
||
133 | } |
||
134 | |||
135 | void Graphical_UI::setFeatureFlowImage(QImage qimage){
|
||
136 | feature_flow_image_label->setAlignment(Qt::AlignCenter); |
||
137 | feature_flow_image_label->setPixmap(QPixmap::fromImage(qimage)); |
||
138 | } |
||
139 | void Graphical_UI::setVisualImage(QImage qimage){
|
||
140 | if(visual_image_label->isVisible()){
|
||
141 | visual_image_label->setPixmap(QPixmap::fromImage(qimage)); |
||
142 | visual_image_label->repaint(); |
||
143 | } |
||
144 | } |
||
145 | |||
146 | void Graphical_UI::setDepthImage(QImage qimage){
|
||
147 | if(depth_image_label->isVisible()){
|
||
148 | depth_image_label->setPixmap(QPixmap::fromImage(qimage)); |
||
149 | depth_image_label->repaint(); |
||
150 | } |
||
151 | } |
||
152 | |||
153 | void Graphical_UI::setTransformation(QString transf){
|
||
154 | transformationMatrix = transf; |
||
155 | } |
||
156 | |||
157 | void Graphical_UI::resetCmd() {
|
||
158 | Q_EMIT reset(); |
||
159 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->reset(); |
||
160 | QString message = tr("Graph Reset");
|
||
161 | statusBar()->showMessage(message); |
||
162 | infoLabel->setText("A fresh new graph is waiting");
|
||
163 | } |
||
164 | |||
165 | void Graphical_UI::setStatus(QString message){
|
||
166 | statusBar()->showMessage(message); |
||
167 | } |
||
168 | void Graphical_UI::setInfo2(QString message){
|
||
169 | infoLabel2->setText(message); |
||
170 | } |
||
171 | void Graphical_UI::setInfo(QString message){
|
||
172 | infoLabel->setText(message); |
||
173 | } |
||
174 | |||
175 | void Graphical_UI::quickSaveAll() {
|
||
176 | Q_EMIT saveAllClouds(filename); |
||
177 | QString message = tr("Saving Whole Model to ");
|
||
178 | message.append(filename); |
||
179 | statusBar()->showMessage(message); |
||
180 | //infoLabel->setText(message);
|
||
181 | } |
||
182 | void Graphical_UI::saveAll() {
|
||
183 | filename = QFileDialog::getSaveFileName(this, "Save Point CLoud to File", filename, tr("PCD (*.pcd);;PLY (*ply)")); |
||
184 | Q_EMIT saveAllClouds(filename); |
||
185 | QString message = tr("Saving Whole Model");
|
||
186 | statusBar()->showMessage(message); |
||
187 | //infoLabel->setText(message);
|
||
188 | } |
||
189 | void Graphical_UI::showEdgeErrors() {
|
||
190 | QString myfilename = QFileDialog::getSaveFileName(this, "Save Current Trajectory Estimate", "trajectory", tr("All Files (*.*)")); |
||
191 | Q_EMIT printEdgeErrors(myfilename); |
||
192 | QString message = tr("Triggering Edge Printing");
|
||
193 | statusBar()->showMessage(message); |
||
194 | } |
||
195 | void Graphical_UI::optimizeGraphTrig() {
|
||
196 | Q_EMIT optimizeGraph(); |
||
197 | QString message = tr("Triggering Optimizer");
|
||
198 | statusBar()->showMessage(message); |
||
199 | } |
||
200 | void Graphical_UI::saveTrajectoryDialog() {
|
||
201 | QString myfilename = QFileDialog::getSaveFileName(this, "Save Current Trajectory Estimate", "trajectory", tr("All Files (*.*)")); |
||
202 | Q_EMIT saveTrajectory(myfilename); |
||
203 | QString message = tr("Saving current trajectory estimate (and possibly ground truth).");
|
||
204 | statusBar()->showMessage(message); |
||
205 | } |
||
206 | void Graphical_UI::saveIndividual() {
|
||
207 | QString tmpfilename(filename); |
||
208 | tmpfilename.remove(".pcd", Qt::CaseInsensitive);
|
||
209 | tmpfilename.remove(".ply", Qt::CaseInsensitive);
|
||
210 | filename = QFileDialog::getSaveFileName(this, "Save point cloud to one file per node", tmpfilename, tr("PCD (*.pcd)")); |
||
211 | Q_EMIT saveIndividualClouds(filename); |
||
212 | QString message = tr("Saving Model Node-Wise");
|
||
213 | statusBar()->showMessage(message); |
||
214 | //infoLabel->setText(message);
|
||
215 | } |
||
216 | |||
217 | void Graphical_UI::sendAll() {
|
||
218 | Q_EMIT sendAllClouds(); |
||
219 | QString message = tr("Sending Whole Model");
|
||
220 | statusBar()->showMessage(message); |
||
221 | //infoLabel->setText(message);
|
||
222 | } |
||
223 | void Graphical_UI::setMax() {
|
||
224 | bool ok;
|
||
225 | double value = QInputDialog::getDouble(this, tr("Set Max Depth"), |
||
226 | tr("Enter Max Depth [in cm]\n (negativ if no Filtering is required):"), -100.00, -10000000, 10000000, 2, &ok); |
||
227 | if(ok){
|
||
228 | Q_EMIT setMaxDepth(value/100.0); |
||
229 | } |
||
230 | } |
||
231 | void Graphical_UI::pruneEdgesWithHighError(){
|
||
232 | bool ok;
|
||
233 | float value = QInputDialog::getDouble(this, tr("Set Max Edge Error"), |
||
234 | tr("No Text"), 1.00, -10000000, 10000000, 2, &ok); |
||
235 | if(ok){
|
||
236 | Q_EMIT pruneEdgesWithErrorAbove(value); |
||
237 | } |
||
238 | } |
||
239 | void Graphical_UI::sendFinished() {
|
||
240 | |||
241 | QString message = tr("Finished Sending");
|
||
242 | statusBar()->showMessage(message); |
||
243 | //infoLabel->setText(message);
|
||
244 | } |
||
245 | |||
246 | void Graphical_UI::getOneFrameCmd() {
|
||
247 | Q_EMIT getOneFrame(); |
||
248 | QString message = tr("Getting a single frame");
|
||
249 | statusBar()->showMessage(message); |
||
250 | //infoLabel->setText(message);
|
||
251 | } |
||
252 | void Graphical_UI::deleteLastFrameCmd() {
|
||
253 | Q_EMIT deleteLastFrame(); |
||
254 | QString message = tr("Deleting the last node from the graph");
|
||
255 | statusBar()->showMessage(message); |
||
256 | //infoLabel->setText(message);
|
||
257 | } |
||
258 | void Graphical_UI::bagRecording(bool pause_on) { |
||
259 | Q_EMIT toggleBagRecording(); |
||
260 | if(pause_on) {
|
||
261 | QString message = tr("Recording Bagfile.");
|
||
262 | statusBar()->showMessage(message); |
||
263 | //infoLabel->setText(message);
|
||
264 | } else {
|
||
265 | QString message = tr("Stopped Recording.");
|
||
266 | statusBar()->showMessage(message); |
||
267 | //infoLabel->setText(message);
|
||
268 | } |
||
269 | } |
||
270 | void Graphical_UI::pause(bool pause_on) { |
||
271 | Q_EMIT togglePause(); |
||
272 | if(pause_on) {
|
||
273 | QString message = tr("Processing.");
|
||
274 | statusBar()->showMessage(message); |
||
275 | //infoLabel->setText(message);
|
||
276 | } else {
|
||
277 | QString message = tr("Stopped processing.");
|
||
278 | statusBar()->showMessage(message); |
||
279 | //infoLabel->setText(message);
|
||
280 | } |
||
281 | } |
||
282 | |||
283 | void Graphical_UI::help() {
|
||
284 | QMessageBox::about(this, tr("Help Menu"), /**menuHelpText +*/ *mouseHelpText ); |
||
285 | } |
||
286 | void Graphical_UI::about() {
|
||
287 | QMessageBox::about(this, tr("About RGBDSLAM"), *infoText + *licenseText); |
||
288 | } |
||
289 | void Graphical_UI::lastTransformationMatrix() {
|
||
290 | QMessageBox::information(this, tr("Current Transformation Matrix"), transformationMatrix); |
||
291 | } |
||
292 | |||
293 | void Graphical_UI::toggleTriangulation() {
|
||
294 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->toggleTriangulation(); |
||
295 | } |
||
296 | |||
297 | void Graphical_UI::set2DStream(bool is_on) { |
||
298 | if(is_on){
|
||
299 | visual_image_label->show(); |
||
300 | depth_image_label->show(); |
||
301 | feature_flow_image_label->show(); |
||
302 | } else {
|
||
303 | visual_image_label->hide(); |
||
304 | depth_image_label->hide(); |
||
305 | feature_flow_image_label->hide(); |
||
306 | } |
||
307 | } |
||
308 | |||
309 | void Graphical_UI::set3DDisplay(bool is_on) { |
||
310 | if(!ParameterServer::instance()->get<bool>("use_glwidget")) return; |
||
311 | if(is_on){ glviewer->show(); }
|
||
312 | else { glviewer->hide(); }
|
||
313 | } |
||
314 | |||
315 | |||
316 | void Graphical_UI::createMenus() {
|
||
317 | //these are the menus created here
|
||
318 | QMenu *graphMenu; |
||
319 | QMenu *actionMenu; |
||
320 | QMenu *viewMenu; |
||
321 | QMenu *helpMenu; |
||
322 | |||
323 | //Graph Menu
|
||
324 | graphMenu = menuBar()->addMenu(tr("&Graph"));
|
||
325 | |||
326 | QAction *quickSaveAct = new QAction(tr("&Save"), this); |
||
327 | quickSaveAct->setShortcuts(QKeySequence::Save); |
||
328 | quickSaveAct->setStatusTip(tr("Save all stored point clouds with common coordinate frame to a pcd file"));
|
||
329 | connect(quickSaveAct, SIGNAL(triggered()), this, SLOT(quickSaveAll()));
|
||
330 | graphMenu->addAction(quickSaveAct); |
||
331 | |||
332 | |||
333 | QAction *saveAct = new QAction(tr("&Save as..."), this); |
||
334 | saveAct->setShortcuts(QKeySequence::SaveAs); |
||
335 | saveAct->setStatusTip(tr("Save all stored point clouds with common coordinate frame"));
|
||
336 | connect(saveAct, SIGNAL(triggered()), this, SLOT(saveAll()));
|
||
337 | graphMenu->addAction(saveAct); |
||
338 | |||
339 | QAction *saveIndiAct = new QAction(tr("&Save Node-Wise..."), this); |
||
340 | saveIndiAct->setShortcut(QString("Ctrl+N"));
|
||
341 | saveIndiAct->setStatusTip(tr("Save stored point clouds in individual files"));
|
||
342 | connect(saveIndiAct, SIGNAL(triggered()), this, SLOT(saveIndividual()));
|
||
343 | graphMenu->addAction(saveIndiAct); |
||
344 | |||
345 | QAction *sendAct = new QAction(tr("&Send Model"), this); |
||
346 | sendAct->setShortcut(QString("Ctrl+M"));
|
||
347 | sendAct->setStatusTip(tr("Send out all stored point clouds with corrected transform"));
|
||
348 | connect(sendAct, SIGNAL(triggered()), this, SLOT(sendAll()));
|
||
349 | graphMenu->addAction(sendAct); |
||
350 | |||
351 | graphMenu->addSeparator(); |
||
352 | |||
353 | QAction *exitAct = new QAction(tr("E&xit"), this); |
||
354 | exitAct->setShortcuts(QKeySequence::Quit); |
||
355 | exitAct->setStatusTip(tr("Exit the application"));
|
||
356 | connect(exitAct, SIGNAL(triggered()), this, SLOT(close()));
|
||
357 | graphMenu->addAction(exitAct); |
||
358 | |||
359 | |||
360 | //Processing Menu
|
||
361 | actionMenu = menuBar()->addMenu(tr("&Processing"));
|
||
362 | |||
363 | QAction *newAct; |
||
364 | newAct = new QAction(tr("&Reset"), this); |
||
365 | newAct->setShortcut(QString("Ctrl+R"));
|
||
366 | newAct->setStatusTip(tr("Reset the graph, clear all data collected"));
|
||
367 | newAct->setIcon(QIcon::fromTheme("document-new"));//doesn't work (for gnome?) |
||
368 | connect(newAct, SIGNAL(triggered()), this, SLOT(resetCmd()));
|
||
369 | actionMenu->addAction(newAct); |
||
370 | |||
371 | QAction *pauseAct = new QAction(tr("&Process"), this); |
||
372 | pauseAct->setShortcut(QString(" "));
|
||
373 | pauseAct->setCheckable(true);
|
||
374 | pauseAct->setChecked(!ParameterServer::instance()->get<bool>("start_paused")); |
||
375 | pauseAct->setStatusTip(tr("Start/stop processing of frames"));
|
||
376 | pauseAct->setIcon(QIcon::fromTheme("media-playback-start"));//doesn't work (for gnome?) |
||
377 | connect(pauseAct, SIGNAL(toggled(bool)), this, SLOT(pause(bool))); |
||
378 | actionMenu->addAction(pauseAct); |
||
379 | |||
380 | QAction *bagRecordingAct = new QAction(tr("&Bagfile Recording"), this); |
||
381 | bagRecordingAct->setShortcut(QString("R"));
|
||
382 | bagRecordingAct->setCheckable(true);
|
||
383 | bagRecordingAct->setChecked(false);
|
||
384 | bagRecordingAct->setStatusTip(tr("Start/stop recording of frames to bagfile"));
|
||
385 | bagRecordingAct->setIcon(QIcon::fromTheme("media-playback-start"));//doesn't work (for gnome?) |
||
386 | connect(bagRecordingAct, SIGNAL(toggled(bool)), this, SLOT(bagRecording(bool))); |
||
387 | actionMenu->addAction(bagRecordingAct); |
||
388 | |||
389 | QAction *compareAct = new QAction(tr("Save Trajectory &Estimate"), this); |
||
390 | compareAct->setShortcut(QString("Ctrl+E"));
|
||
391 | compareAct->setStatusTip(tr("Save trajectory estimate (and ground truth trajectory if available) for external evaluation."));
|
||
392 | connect(compareAct, SIGNAL(triggered()), this, SLOT(saveTrajectoryDialog()));
|
||
393 | actionMenu->addAction(compareAct); |
||
394 | |||
395 | QAction *optimizeAct = new QAction(tr("Optimize Trajectory &Estimate"), this); |
||
396 | optimizeAct->setShortcut(QString("Ctrl+Shift+O"));
|
||
397 | optimizeAct->setStatusTip(tr("Compute two iterations with g2o"));
|
||
398 | connect(optimizeAct, SIGNAL(triggered()), this, SLOT(optimizeGraphTrig()));
|
||
399 | actionMenu->addAction(optimizeAct); |
||
400 | |||
401 | QAction *showErrorAct = new QAction(tr("Show Edge Errors"), this); |
||
402 | showErrorAct->setShortcut(QString("Ctrl+Shift+E"));
|
||
403 | showErrorAct->setStatusTip(tr(""));
|
||
404 | connect(showErrorAct, SIGNAL(triggered()), this, SLOT(showEdgeErrors()));
|
||
405 | actionMenu->addAction(showErrorAct); |
||
406 | |||
407 | QAction *maxAct = new QAction(tr("Set Maximum &Depth"), this); |
||
408 | maxAct->setShortcut(QString("Ctrl+D"));
|
||
409 | maxAct->setStatusTip(tr("Set the Maximum Depth a Point can have (negativ if no Filtering is required)"));
|
||
410 | connect(maxAct, SIGNAL(triggered()), this, SLOT(setMax()));
|
||
411 | actionMenu->addAction(maxAct); |
||
412 | |||
413 | QAction *pruneAct = new QAction(tr("Set Ma&ximum Edge Error"), this); |
||
414 | pruneAct->setShortcut(QString("Ctrl+X"));
|
||
415 | pruneAct->setStatusTip(tr("Set the Maximum Allowed for Edges"));
|
||
416 | connect(pruneAct, SIGNAL(triggered()), this, SLOT(pruneEdgesWithHighError()));
|
||
417 | actionMenu->addAction(pruneAct); |
||
418 | |||
419 | QAction *oneFrameAct = new QAction(tr("Capture One& Frame"), this); |
||
420 | oneFrameAct->setShortcuts(QKeySequence::InsertParagraphSeparator); |
||
421 | oneFrameAct->setStatusTip(tr("Process one frame only"));
|
||
422 | connect(oneFrameAct, SIGNAL(triggered()), this, SLOT(getOneFrameCmd()));
|
||
423 | actionMenu->addAction(oneFrameAct); |
||
424 | |||
425 | QAction *delFrameAct = new QAction(tr("&Delete Last Node"), this); |
||
426 | delFrameAct->setShortcut(QString("Backspace"));
|
||
427 | delFrameAct->setStatusTip(tr("Remove last node from graph"));
|
||
428 | connect(delFrameAct, SIGNAL(triggered()), this, SLOT(deleteLastFrameCmd()));
|
||
429 | actionMenu->addAction(delFrameAct); |
||
430 | |||
431 | |||
432 | //View Menu
|
||
433 | viewMenu = menuBar()->addMenu(tr("&View"));
|
||
434 | |||
435 | QAction *toggleGLViewerAct = new QAction(tr("Toggle &3D Display"), this); |
||
436 | toggleGLViewerAct->setShortcut(QString("3"));
|
||
437 | toggleGLViewerAct->setCheckable(true);
|
||
438 | toggleGLViewerAct->setChecked(true);
|
||
439 | toggleGLViewerAct->setStatusTip(tr("Turn off the OpenGL Display of the Accumulated PointClouds"));
|
||
440 | connect(toggleGLViewerAct, SIGNAL(toggled(bool)), this, SLOT(set3DDisplay(bool))); |
||
441 | viewMenu->addAction(toggleGLViewerAct); |
||
442 | |||
443 | QAction *toggleStreamAct = new QAction(tr("Toggle &2D Stream"), this); |
||
444 | toggleStreamAct->setShortcut(QString("2"));
|
||
445 | toggleStreamAct->setCheckable(true);
|
||
446 | toggleStreamAct->setChecked(true);
|
||
447 | toggleStreamAct->setStatusTip(tr("Turn off the Image Stream"));
|
||
448 | connect(toggleStreamAct, SIGNAL(toggled(bool)), this, SLOT(set2DStream(bool))); |
||
449 | viewMenu->addAction(toggleStreamAct); |
||
450 | |||
451 | QAction *toggleTriangulationAct = new QAction(tr("&Toggle Rendering"), this); |
||
452 | toggleTriangulationAct->setShortcut(QString("T"));
|
||
453 | toggleTriangulationAct->setStatusTip(tr("Switch between surface, wireframe and point cloud"));
|
||
454 | connect(toggleTriangulationAct, SIGNAL(triggered(bool)), this, SLOT(toggleTriangulation())); |
||
455 | viewMenu->addAction(toggleTriangulationAct); |
||
456 | |||
457 | QAction *toggleFollowAct = new QAction(tr("&Follow Camera"), this); |
||
458 | toggleFollowAct->setShortcut(QString("F"));
|
||
459 | toggleFollowAct->setCheckable(true);
|
||
460 | toggleFollowAct->setChecked(true);
|
||
461 | toggleFollowAct->setStatusTip(tr("Always use viewpoint of last frame (except zoom)"));
|
||
462 | connect(toggleFollowAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleFollowMode(bool))); |
||
463 | viewMenu->addAction(toggleFollowAct); |
||
464 | |||
465 | QAction *toggleShowAxisAct = new QAction(tr("Show Pose &Graph"), this); |
||
466 | toggleShowAxisAct->setShortcut(QString("G"));
|
||
467 | toggleShowAxisAct->setCheckable(true);
|
||
468 | toggleShowAxisAct->setChecked(ParameterServer::instance()->get<bool>("show_axis")); |
||
469 | toggleShowAxisAct->setStatusTip(tr("Display Pose Graph as Axes Connected by Lines"));
|
||
470 | connect(toggleShowAxisAct, SIGNAL(toggled(bool)), glviewer, SLOT(toggleShowAxis(bool))); |
||
471 | viewMenu->addAction(toggleShowAxisAct); |
||
472 | |||
473 | |||
474 | //Help Menu
|
||
475 | helpMenu = menuBar()->addMenu(tr("&Help"));
|
||
476 | |||
477 | QAction *transfAct = new QAction(tr("Current Transformation &Matrix"), this); |
||
478 | transfAct->setShortcut(QString("Ctrl+T"));
|
||
479 | transfAct->setStatusTip(tr("Show the Current Transformation Matrix"));
|
||
480 | connect(transfAct, SIGNAL(triggered()), this, SLOT(lastTransformationMatrix()));
|
||
481 | helpMenu->addAction(transfAct); |
||
482 | |||
483 | QAction *helpAct = new QAction(tr("&Usage Help"), this); |
||
484 | helpAct->setShortcuts(QKeySequence::HelpContents); |
||
485 | helpAct->setStatusTip(tr("Show usage information"));
|
||
486 | connect(helpAct, SIGNAL(triggered()), this, SLOT(help()));
|
||
487 | helpMenu->addAction(helpAct); |
||
488 | |||
489 | QAction *aboutAct = new QAction(tr("&About RGBDSLAM"), this); |
||
490 | aboutAct->setShortcut(QString("Ctrl+A"));
|
||
491 | aboutAct->setStatusTip(tr("Show information about RGBDSLAM"));
|
||
492 | connect(aboutAct, SIGNAL(triggered()), this, SLOT(about()));
|
||
493 | helpMenu->addAction(aboutAct); |
||
494 | |||
495 | } |
||
496 | |||
497 | void Graphical_UI::addPointCloud(pointcloud_type * pc, QMatrix4x4 transform){
|
||
498 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->addPointCloud(pc, transform); |
||
499 | } |
||
500 | void Graphical_UI::deleteLastNode(){
|
||
501 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->deleteLastNode(); |
||
502 | } |
||
503 | void Graphical_UI::resetGLViewer(){
|
||
504 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->reset(); |
||
505 | } |
||
506 | void Graphical_UI::setGraphEdges(QList<QPair<int, int> >* list){ |
||
507 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->setEdges(list); |
||
508 | } |
||
509 | void Graphical_UI::updateTransforms(QList<QMatrix4x4>* transforms){
|
||
510 | if(ParameterServer::instance()->get<bool>("use_glwidget")) glviewer->updateTransforms(transforms); |
||
511 | } |
||
512 | |||
513 | GLViewer* Graphical_UI::getGLViewer() { |
||
514 | return glviewer;
|
||
515 | } |