MainWindow.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "find_object/MainWindow.h"
29 #include "find_object/Camera.h"
30 #include "find_object/Settings.h"
31 #include "find_object/TcpServer.h"
32 #include "find_object/FindObject.h"
34 #include "find_object/ObjWidget.h"
35 #include "find_object/QtOpenCV.h"
36 
37 #include "AddObjectDialog.h"
38 #include "ui_mainWindow.h"
39 #include "KeypointItem.h"
40 #include "RectItem.h"
41 #include "ParametersToolBox.h"
42 #include "AboutDialog.h"
43 #include "rtabmap/PdfPlot.h"
44 #include "Vocabulary.h"
45 #include "ObjSignature.h"
46 
47 #include <iostream>
48 #include <stdio.h>
49 
50 #include "opencv2/calib3d/calib3d.hpp"
51 #include "opencv2/imgproc/imgproc.hpp"
52 #include <opencv2/opencv_modules.hpp>
53 #if CV_MAJOR_VERSION < 3
54 #include <opencv2/gpu/gpu.hpp>
55 #else
56 #include <opencv2/core/cuda.hpp>
57 #endif
58 
59 #include <QtCore/QTextStream>
60 #include <QtCore/QFile>
61 #include <QtCore/QBuffer>
62 #include <QtCore/QThread>
63 #include <QtCore/QLineF>
64 
65 #include <QFileDialog>
66 #include <QMessageBox>
67 #include <QGraphicsScene>
68 #include <QGraphicsRectItem>
69 #include <QSpinBox>
70 #include <QStatusBar>
71 #include <QProgressDialog>
72 #include <QCloseEvent>
73 #include <QCheckBox>
74 #include <QScrollBar>
75 #include <QInputDialog>
76 
77 #include "utilite/UDirectory.h"
78 
79 namespace find_object {
80 
81 // Camera ownership transferred
82 MainWindow::MainWindow(FindObject * findObject, Camera * camera, QWidget * parent) :
83  QMainWindow(parent),
84  camera_(camera),
85  findObject_(findObject),
86  likelihoodCurve_(0),
87  inliersCurve_(0),
88  lowestRefreshRate_(99),
89  objectsModified_(false),
90  tcpServer_(0)
91 {
92  UASSERT(findObject_ != 0);
93 
94  ui_ = new Ui_mainWindow();
95  ui_->setupUi(this);
96  aboutDialog_ = new AboutDialog(this);
97  this->setStatusBar(new QStatusBar());
98 
99  likelihoodCurve_ = new rtabmap::PdfPlotCurve("Likelihood", &imagesMap_, this);
100  inliersCurve_ = new rtabmap::PdfPlotCurve("Inliers", &imagesMap_, this);
101  likelihoodCurve_->setPen(QPen(Qt::blue));
102  inliersCurve_->setPen(QPen(Qt::red));
103  ui_->likelihoodPlot->addCurve(likelihoodCurve_, false);
104  ui_->likelihoodPlot->addCurve(inliersCurve_, false);
105  ui_->likelihoodPlot->setGraphicsView(true);
106 
107  ui_->dockWidget_statistics->setVisible(false);
108  ui_->dockWidget_parameters->setVisible(false);
109  ui_->dockWidget_plot->setVisible(false);
110  ui_->widget_controls->setVisible(false);
111 
112  QByteArray geometry;
113  QByteArray state;
114  Settings::loadWindowSettings(geometry, state);
115  this->restoreGeometry(geometry);
116  this->restoreState(state);
118 
119  ui_->toolBox->setupUi();
120 
121  if(!camera_)
122  {
123  camera_ = new Camera(this);
124  }
125  else
126  {
127  camera_->setParent(this);
128  ui_->toolBox->getParameterWidget(Settings::kCamera_1deviceId())->setEnabled(false);
129  ui_->toolBox->getParameterWidget(Settings::kCamera_2imageWidth())->setEnabled(false);
130  ui_->toolBox->getParameterWidget(Settings::kCamera_3imageHeight())->setEnabled(false);
131  ui_->toolBox->getParameterWidget(Settings::kCamera_5mediaPath())->setEnabled(false);
132  ui_->toolBox->getParameterWidget(Settings::kCamera_6useTcpCamera())->setEnabled(false);
133  ui_->toolBox->getParameterWidget(Settings::kCamera_8port())->setEnabled(false);
134  ui_->toolBox->getParameterWidget(Settings::kCamera_9queueSize())->setEnabled(false);
135  ui_->actionCamera_from_video_file->setVisible(false);
136  ui_->actionCamera_from_TCP_IP->setVisible(false);
137  ui_->actionCamera_from_directory_of_images->setVisible(false);
138  ui_->actionLoad_scene_from_file->setVisible(false);
139  }
140 
141 #if CV_MAJOR_VERSION < 3
142  if(cv::gpu::getCudaEnabledDeviceCount() == 0)
143 #else
144  if(cv::cuda::getCudaEnabledDeviceCount() == 0)
145 #endif
146  {
147 #if FINDOBJECT_NONFREE == 1
148  ui_->toolBox->updateParameter(Settings::kFeature2D_SURF_gpu());
149  ui_->toolBox->getParameterWidget(Settings::kFeature2D_SURF_gpu())->setEnabled(false);
150  ui_->toolBox->getParameterWidget(Settings::kFeature2D_SURF_keypointsRatio())->setEnabled(false);
151 #endif
152  ui_->toolBox->updateParameter(Settings::kFeature2D_Fast_gpu());
153  ui_->toolBox->updateParameter(Settings::kFeature2D_ORB_gpu());
154  ui_->toolBox->updateParameter(Settings::kNearestNeighbor_BruteForce_gpu());
155  ui_->toolBox->getParameterWidget(Settings::kFeature2D_Fast_gpu())->setEnabled(false);
156  ui_->toolBox->getParameterWidget(Settings::kFeature2D_Fast_keypointsRatio())->setEnabled(false);
157  ui_->toolBox->getParameterWidget(Settings::kFeature2D_ORB_gpu())->setEnabled(false);
158  ui_->toolBox->getParameterWidget(Settings::kNearestNeighbor_BruteForce_gpu())->setEnabled(false);
159  }
160 
161  connect((QDoubleSpinBox*)ui_->toolBox->getParameterWidget(Settings::kCamera_4imageRate()),
162  SIGNAL(editingFinished()),
163  camera_,
164  SLOT(updateImageRate()));
165  ui_->menuView->addAction(ui_->dockWidget_statistics->toggleViewAction());
166  ui_->menuView->addAction(ui_->dockWidget_parameters->toggleViewAction());
167  ui_->menuView->addAction(ui_->dockWidget_objects->toggleViewAction());
168  ui_->menuView->addAction(ui_->dockWidget_plot->toggleViewAction());
169  connect(ui_->toolBox, SIGNAL(parametersChanged(const QStringList &)), this, SLOT(notifyParametersChanged(const QStringList &)));
170 
171  ui_->imageView_source->setTextLabel(tr("Press \"space\" to start the camera or drop an image here..."));
172  ui_->imageView_source->setMirrorView(Settings::getGeneral_mirrorView());
173  connect((QCheckBox*)ui_->toolBox->getParameterWidget(Settings::kGeneral_mirrorView()),
174  SIGNAL(stateChanged(int)),
175  this,
176  SLOT(updateMirrorView()));
177 
178  ui_->widget_controls->setVisible(Settings::getGeneral_controlsShown());
179  connect((QCheckBox*)ui_->toolBox->getParameterWidget(Settings::kGeneral_controlsShown()),
180  SIGNAL(stateChanged(int)),
181  this,
182  SLOT(showHideControls()));
183 
184  //buttons
185  connect(ui_->pushButton_restoreDefaults, SIGNAL(clicked()), ui_->toolBox, SLOT(resetCurrentPage()));
186  connect(ui_->pushButton_updateObjects, SIGNAL(clicked()), this, SLOT(updateObjects()));
187  connect(ui_->horizontalSlider_objectsSize, SIGNAL(valueChanged(int)), this, SLOT(updateObjectsSize()));
188 
189  ui_->actionStop_camera->setEnabled(false);
190  ui_->actionPause_camera->setEnabled(false);
191  ui_->actionSave_objects->setEnabled(false);
192  ui_->actionSave_session->setEnabled(false);
193 
194  // Actions
195  connect(ui_->actionAdd_object_from_scene, SIGNAL(triggered()), this, SLOT(addObjectFromScene()));
196  connect(ui_->actionAdd_objects_from_files, SIGNAL(triggered()), this, SLOT(addObjectsFromFiles()));
197  connect(ui_->actionLoad_scene_from_file, SIGNAL(triggered()), this, SLOT(loadSceneFromFile()));
198  connect(ui_->actionStart_camera, SIGNAL(triggered()), this, SLOT(startProcessing()));
199  connect(ui_->actionStop_camera, SIGNAL(triggered()), this, SLOT(stopProcessing()));
200  connect(ui_->actionPause_camera, SIGNAL(triggered()), this, SLOT(pauseProcessing()));
201  connect(ui_->actionExit, SIGNAL(triggered()), this, SLOT(close()));
202  connect(ui_->actionSave_objects, SIGNAL(triggered()), this, SLOT(saveObjects()));
203  connect(ui_->actionLoad_objects, SIGNAL(triggered()), this, SLOT(loadObjects()));
204  connect(ui_->actionCamera_from_video_file, SIGNAL(triggered()), this, SLOT(setupCameraFromVideoFile()));
205  connect(ui_->actionCamera_from_directory_of_images, SIGNAL(triggered()), this, SLOT(setupCameraFromImagesDirectory()));
206  connect(ui_->actionCamera_from_TCP_IP, SIGNAL(triggered()), this, SLOT(setupCameraFromTcpIp()));
207  connect(ui_->actionAbout, SIGNAL(triggered()), aboutDialog_ , SLOT(exec()));
208  connect(ui_->actionRestore_all_default_settings, SIGNAL(triggered()), ui_->toolBox, SLOT(resetAllPages()));
209  connect(ui_->actionRemove_all_objects, SIGNAL(triggered()), this, SLOT(removeAllObjects()));
210  connect(ui_->actionSave_settings, SIGNAL(triggered()), this, SLOT(saveSettings()));
211  connect(ui_->actionLoad_settings, SIGNAL(triggered()), this, SLOT(loadSettings()));
212  connect(ui_->actionSave_session, SIGNAL(triggered()), this, SLOT(saveSession()));
213  connect(ui_->actionLoad_session, SIGNAL(triggered()), this, SLOT(loadSession()));
214  connect(ui_->actionSave_vocabulary, SIGNAL(triggered()), this, SLOT(saveVocabulary()));
215  connect(ui_->actionLoad_vocabulary, SIGNAL(triggered()), this, SLOT(loadVocabulary()));
216  connect(ui_->actionShow_objects_features, SIGNAL(triggered()), this, SLOT(showObjectsFeatures()));
217  connect(ui_->actionHide_objects_features, SIGNAL(triggered()), this, SLOT(hideObjectsFeatures()));
218 
219  connect(ui_->pushButton_play, SIGNAL(clicked()), this, SLOT(startProcessing()));
220  connect(ui_->pushButton_stop, SIGNAL(clicked()), this, SLOT(stopProcessing()));
221  connect(ui_->pushButton_pause, SIGNAL(clicked()), this, SLOT(pauseProcessing()));
222  connect(ui_->horizontalSlider_frames, SIGNAL(valueChanged(int)), this, SLOT(moveCameraFrame(int)));
223  connect(ui_->horizontalSlider_frames, SIGNAL(valueChanged(int)), ui_->label_frame, SLOT(setNum(int)));
224  ui_->pushButton_play->setVisible(true);
225  ui_->pushButton_pause->setVisible(false);
226  ui_->pushButton_stop->setEnabled(false);
227  ui_->horizontalSlider_frames->setEnabled(false);
228  ui_->label_frame->setVisible(false);
229 
230  ui_->objects_area->addAction(ui_->actionAdd_object_from_scene);
231  ui_->objects_area->addAction(ui_->actionAdd_objects_from_files);
232  ui_->objects_area->setContextMenuPolicy(Qt::ActionsContextMenu);
233 
234  ui_->actionStart_camera->setShortcut(Qt::Key_Space);
235  ui_->actionPause_camera->setShortcut(Qt::Key_Space);
236 
237  ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && !UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()));
238  ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()));
239  ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
240 
241  ui_->label_ipAddress->setTextInteractionFlags(Qt::TextSelectableByMouse);
242  ui_->label_port->setTextInteractionFlags(Qt::TextSelectableByMouse);
243  setupTCPServer();
244 
245  if(findObject_->objects().size())
246  {
247  // show objects already loaded in FindObject
248  for(QMap<int, ObjSignature *>::const_iterator iter = findObject_->objects().constBegin();
249  iter!=findObject_->objects().constEnd();
250  ++iter)
251  {
252  ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), iter.value()->words(), cvtCvMat2QImage(iter.value()->image()));
253  objWidgets_.insert(obj->id(), obj);
254  this->showObject(obj);
255  }
256  ui_->actionSave_objects->setEnabled(true);
257  ui_->actionSave_session->setEnabled(true);
258  }
259  if(findObject_->vocabulary()->size())
260  {
261  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
262  ui_->actionSave_session->setEnabled(true);
263  }
264 
265 
266  if(Settings::getGeneral_autoStartCamera())
267  {
268  // Set 1 msec to see state on the status bar.
269  QTimer::singleShot(1, this, SLOT(startProcessing()));
270  }
271 
272  //Setup drag and drop images
273  connect(ui_->imageDrop_objects, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(addObjectsFromFiles(const QStringList &)));
274  connect(ui_->imageDrop_scene, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(loadSceneFromFile(const QStringList &)));
275 
276  ui_->imageView_source->setFocus();
277 }
278 
280 {
281  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
282  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
283  camera_->stop();
284  qDeleteAll(objWidgets_);
285  objWidgets_.clear();
286  delete ui_;
287  delete findObject_;
288 }
289 
290 void MainWindow::closeEvent(QCloseEvent * event)
291 {
292  bool quit = true;
293  this->stopProcessing();
294  if(objectsModified_ && this->isVisible() && objWidgets_.size())
295  {
296  int ret = QMessageBox::question(this, tr("Save new objects"), tr("Do you want to save added objects?"), QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
297  switch(ret)
298  {
299  case QMessageBox::Yes:
300  quit = this->saveObjects();
301  break;
302  case QMessageBox::Cancel:
303  quit = false;
304  break;
305  case QMessageBox::No:
306  default:
307  break;
308  }
309  }
310  if(quit)
311  {
312  Settings::saveWindowSettings(this->saveGeometry(), this->saveState());
313  event->accept();
314  }
315  else
316  {
317  event->ignore();
318  }
319 }
320 
321 void MainWindow::keyPressEvent(QKeyEvent *event)
322 {
323  //catch ctrl-s to save settings
324  if(event->key() == Qt::Key_Space)
325  {
326  if(ui_->actionStart_camera->isEnabled())
327  {
328  startProcessing();
329  }
330  else if(ui_->actionPause_camera->isEnabled())
331  {
332  pauseProcessing();
333  }
334  }
335 }
336 
338 {
339  if(tcpServer_)
340  {
341  tcpServer_->close();
342  delete tcpServer_;
343  }
344  tcpServer_ = new TcpServer(Settings::getGeneral_port(), this);
345  connect(this, SIGNAL(objectsFound(find_object::DetectionInfo)), tcpServer_, SLOT(publishDetectionInfo(find_object::DetectionInfo)));
346  ui_->label_ipAddress->setText(tcpServer_->getHostAddress().toString());
347  ui_->label_port->setNum(tcpServer_->getPort());
348  UINFO("Detection sent on port: %d (IP=%s)", tcpServer_->getPort(), tcpServer_->getHostAddress().toString().toStdString().c_str());
349 
350  //connect services
351  connect(tcpServer_, SIGNAL(addObject(const cv::Mat &, int, const QString &)), this, SLOT(addObjectFromTcp(const cv::Mat &, int, const QString &)));
352  connect(tcpServer_, SIGNAL(removeObject(int)), this, SLOT(removeObject(int)));
353 }
354 
355 void MainWindow::setSourceImageText(const QString & text)
356 {
357  ui_->imageView_source->setTextLabel(text);
358 }
359 
361 {
362  if(objWidgets_.size())
363  {
364  QMessageBox::StandardButton b = QMessageBox::question(this, tr("Loading session..."),
365  tr("There are some objects (%1) already loaded, they will be "
366  "deleted when loading the session. Do you want to continue?").arg(objWidgets_.size()),
367  QMessageBox::Yes | QMessageBox::No, QMessageBox::NoButton);
368  if(b != QMessageBox::Yes)
369  {
370  return;
371  }
372  }
373 
374  QString path = QFileDialog::getOpenFileName(this, tr("Load session..."), Settings::workingDirectory(), "*.bin");
375  if(!path.isEmpty())
376  {
377  qDeleteAll(objWidgets_);
378  objWidgets_.clear();
379  ui_->actionSave_objects->setEnabled(false);
381 
382  if(findObject_->loadSession(path))
383  {
384  //update parameters tool box
385  const ParametersMap & parameters = Settings::getParameters();
386  for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
387  {
388  ui_->toolBox->updateParameter(iter.key());
389  }
390 
391  //update object widgets
392  for(QMap<int, ObjSignature *>::const_iterator iter=findObject_->objects().constBegin(); iter!=findObject_->objects().constEnd();++iter)
393  {
394  if(iter.value())
395  {
396  ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), iter.value()->words(), cvtCvMat2QImage(iter.value()->image()));
397  objWidgets_.insert(obj->id(), obj);
398  ui_->actionSave_objects->setEnabled(true);
399  ui_->actionSave_session->setEnabled(true);
400  this->showObject(obj);
401 
402  //update object labels
403  QLabel * title = this->findChild<QLabel*>(QString("%1title").arg(iter.value()->id()));
404  title->setText(QString("%1 (%2)").arg(iter.value()->id()).arg(QString::number(iter.value()->keypoints().size())));
405  }
406 
407  }
408 
409  QMessageBox::information(this, tr("Session loaded!"), tr("Session \"%1\" successfully loaded (%2 objects)!").arg(path).arg(objWidgets_.size()));
410 
411  if(!camera_->isRunning() && !sceneImage_.empty())
412  {
413  this->update(sceneImage_);
414  }
415  }
416  }
417 }
419 {
420  if(objWidgets_.size())
421  {
422  QString path = QFileDialog::getSaveFileName(this, tr("Save session..."), Settings::workingDirectory(), "*.bin");
423  if(!path.isEmpty())
424  {
425  if(QFileInfo(path).suffix().compare("bin") != 0)
426  {
427  path.append(".bin");
428  }
429 
430  if(findObject_->saveSession(path))
431  {
432  QMessageBox::information(this, tr("Session saved!"), tr("Session \"%1\" successfully saved (%2 objects)!").arg(path).arg(objWidgets_.size()));
433  }
434  }
435  }
436 }
437 
439 {
440  QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), Settings::workingDirectory(), "*.ini");
441  if(!path.isEmpty())
442  {
443  if(QFileInfo(path).suffix().compare("ini") != 0)
444  {
445  path.append(".ini");
446  }
447  loadSettings(path);
448  }
449 }
451 {
452  QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), Settings::workingDirectory(), "*.ini");
453  if(!path.isEmpty())
454  {
455  if(QFileInfo(path).suffix().compare("ini") != 0)
456  {
457  path.append(".ini");
458  }
459  saveSettings(path);
460  }
461 }
462 
463 bool MainWindow::loadSettings(const QString & path)
464 {
465  if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
466  {
467  QByteArray geometry;
468  QByteArray state;
470  Settings::loadWindowSettings(geometry, state, path);
471  this->restoreGeometry(geometry);
472  this->restoreState(state);
473 
474  //update parameters tool box
475  const ParametersMap & parameters = Settings::getParameters();
476  for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
477  {
478  ui_->toolBox->updateParameter(iter.key());
479  }
480 
481  return true;
482  }
483  UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
484  return false;
485 }
486 
487 bool MainWindow::saveSettings(const QString & path) const
488 {
489  if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
490  {
492  Settings::saveWindowSettings(this->saveGeometry(), this->saveState(), path);
493  return true;
494  }
495  UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
496  return false;
497 }
498 
499 int MainWindow::loadObjects(const QString & dirPath, bool recursive)
500 {
501  QList<int> loadedObjects;
502  QString formats = Settings::getGeneral_imageFormats().remove('*').remove('.');
503 
504  QStringList paths;
505  paths.append(dirPath);
506 
507  while(paths.size())
508  {
509  QString currentDir = paths.front();
510  UDirectory dir(currentDir.toStdString(), formats.toStdString());
511  if(dir.isValid())
512  {
513  const std::list<std::string> & names = dir.getFileNames(); // sorted in natural order
514  for(std::list<std::string>::const_iterator iter=names.begin(); iter!=names.end(); ++iter)
515  {
516  int id = this->addObjectFromFile((currentDir.toStdString()+dir.separator()+*iter).c_str());
517  if(id >= 0)
518  {
519  loadedObjects.push_back(id);
520  }
521  }
522  }
523 
524  paths.pop_front();
525 
526  if(recursive)
527  {
528  QDir d(currentDir);
529  QStringList subDirs = d.entryList(QDir::AllDirs|QDir::NoDotAndDotDot, QDir::Name);
530  for(int i=subDirs.size()-1; i>=0; --i)
531  {
532  paths.prepend(currentDir + QDir::separator() + subDirs[i]);
533  }
534  }
535  }
536 
537  if(loadedObjects.size())
538  {
539  this->updateObjects(loadedObjects);
540  }
541 
542  return loadedObjects.size();
543 }
544 
545 int MainWindow::saveObjects(const QString & dirPath)
546 {
547  int count = 0;
548  QDir dir(dirPath);
549  if(dir.exists())
550  {
551  for(QMap<int, ObjWidget*>::const_iterator iter=objWidgets_.constBegin(); iter!=objWidgets_.constEnd(); ++iter)
552  {
553  if(iter.value()->pixmap().save(QString("%1/%2.png").arg(dirPath).arg(iter.key())))
554  {
555  ++count;
556  }
557  else
558  {
559  UERROR("Failed to save object %d", iter.key());
560  }
561  }
562  objectsModified_ = false;
563  }
564  return count;
565 }
566 
568 {
569  QString dirPath = QFileDialog::getExistingDirectory(this, tr("Loading objects... Select a directory."), Settings::workingDirectory());
570  if(!dirPath.isEmpty())
571  {
572  QDir d(dirPath);
573  bool recursive = false;
574  if(d.entryList(QDir::AllDirs | QDir::NoDotAndDotDot).size())
575  {
576  QMessageBox::StandardButton b = QMessageBox::question(
577  this,
578  tr("Loading objects..."),
579  tr("The current directory contains subdirectories. Load objects recursively?"),
580  QMessageBox::Yes|QMessageBox::No,
581  QMessageBox::No);
582  recursive = b == QMessageBox::Yes;
583  }
584 
585  int count = loadObjects(dirPath, recursive);
586  if(count)
587  {
588  QMessageBox::information(this, tr("Loading..."), tr("%1 objects loaded from \"%2\".").arg(count).arg(dirPath));
589  }
590  else
591  {
592  QMessageBox::information(this, tr("Loading..."), tr("No objects loaded from \"%1\"!").arg(dirPath));
593  }
594  }
595 }
597 {
598  QString dirPath = QFileDialog::getExistingDirectory(this, tr("Saving objects... Select a directory."), Settings::workingDirectory());
599  if(!dirPath.isEmpty())
600  {
601  int count = saveObjects(dirPath);
602  if(count)
603  {
604  QMessageBox::information(this, tr("Saving..."), tr("%1 objects saved to \"%2\".").arg(count).arg(dirPath));
605  }
606  else
607  {
608  QMessageBox::warning(this, tr("Saving..."), tr("No objects saved to %1!").arg(dirPath));
609  }
610  return count > 0;
611  }
612  return false;
613 }
614 
616 {
617  if(!Settings::getGeneral_vocabularyFixed() ||
618  !Settings::getGeneral_invertedSearch())
619  {
620  QMessageBox::StandardButton b = QMessageBox::question(this, tr("Load vocabulary..."),
621  tr("Parameters \"General/vocabularyFixed\" and \"General/invertedSearch\" should be enabled to load a vocabulary. "
622  "Do you want to enable them now?"),
623  QMessageBox::Cancel | QMessageBox::Yes);
624  if(b == QMessageBox::Yes)
625  {
626  Settings::setGeneral_vocabularyFixed(true);
627  Settings::setGeneral_invertedSearch(true);
628  }
629  }
630  if(Settings::getGeneral_vocabularyFixed() &&
631  Settings::getGeneral_invertedSearch())
632  {
633  QString path = QFileDialog::getOpenFileName(this, tr("Load vocabulary..."), Settings::workingDirectory(), "Data (*.yaml *.xml)");
634  if(!path.isEmpty())
635  {
636  if(findObject_->loadVocabulary(path))
637  {
638  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
639  ui_->actionSave_session->setEnabled(findObject_->vocabulary()->size() || findObject_->objects().size());
640  QMessageBox::information(this, tr("Loading..."), tr("Vocabulary loaded from \"%1\" (%2 words).").arg(path).arg(findObject_->vocabulary()->size()));
641  }
642  else
643  {
644  QMessageBox::warning(this, tr("Loading..."), tr("Failed to load vocabulary \"%1\"!").arg(path));
645  }
646  }
647  }
648 }
649 
651 {
652  if(findObject_->vocabulary()->size() == 0)
653  {
654  QMessageBox::warning(this, tr("Saving vocabulary..."), tr("Vocabulary is empty!"));
655  return;
656  }
657  QString path = QFileDialog::getSaveFileName(this, tr("Save vocabulary..."), Settings::workingDirectory(), "Data (*.yaml *.xml)");
658  if(!path.isEmpty())
659  {
660  if(QFileInfo(path).suffix().compare("yaml") != 0 && QFileInfo(path).suffix().compare("xml") != 0)
661  {
662  path.append(".yaml");
663  }
664  if(findObject_->saveVocabulary(path))
665  {
666  QMessageBox::information(this, tr("Saving..."), tr("Vocabulary saved to \"%1\" (%2 words).").arg(path).arg(findObject_->vocabulary()->size()));
667  }
668  else
669  {
670  QMessageBox::warning(this, tr("Saving..."), tr("Failed to save vocabulary \"%1\"!").arg(path));
671  }
672  }
673 }
674 
676 {
677  if(object)
678  {
679  objWidgets_.remove(object->id());
680  if(objWidgets_.size() == 0)
681  {
682  ui_->actionSave_objects->setEnabled(false);
683  ui_->actionSave_session->setEnabled(false);
684  }
685  findObject_->removeObject(object->id());
686  object->deleteLater();
687  if(Settings::getGeneral_autoUpdateObjects())
688  {
689  this->updateVocabulary();
690  }
691  if(!camera_->isRunning() && !sceneImage_.empty())
692  {
693  this->update(sceneImage_);
694  }
695  }
696 }
697 
699 {
700  if(objWidgets_.contains(id))
701  {
703  }
704  else
705  {
706  UERROR("Remove object: Object %d not found!", id);
707  }
708 }
709 
711 {
712  qDeleteAll(objWidgets_);
713  objWidgets_.clear();
714  ui_->actionSave_objects->setEnabled(false);
716  if(!camera_->isRunning() && !sceneImage_.empty())
717  {
718  this->update(sceneImage_);
719  }
720 }
721 
723 {
724  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
725  {
726  updateObjectSize(iter.value());
727  }
728 }
729 
731 {
732  if(obj)
733  {
734  int value = ui_->horizontalSlider_objectsSize->value();
735  if((obj->pixmap().width()*value)/100 > 4 && (obj->pixmap().height()*value)/100 > 4)
736  {
737  obj->setVisible(true);
738  obj->setMinimumSize((obj->pixmap().width()*value)/100, (obj->pixmap().height())*value/100);
739  }
740  else
741  {
742  obj->setVisible(false);
743  }
744  }
745 }
746 
748 {
749  bool mirrorView = Settings::getGeneral_mirrorView();
750  ui_->imageView_source->setMirrorView(mirrorView);
751  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
752  {
753  iter.value()->setMirrorView(mirrorView);
754  }
755 }
756 
758 {
759  ui_->widget_controls->setVisible(Settings::getGeneral_controlsShown());
760 }
761 
763 {
764  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
765  {
766  iter.value()->setFeaturesShown(true);
767  }
768 }
769 
771 {
772  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
773  {
774  iter.value()->setFeaturesShown(false);
775  }
776 }
777 
779 {
780  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
781  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
782  AddObjectDialog * dialog;
783  bool resumeCamera = camera_->isRunning();
784  if(camera_->isRunning() || sceneImage_.empty())
785  {
786  dialog = new AddObjectDialog(camera_, cv::Mat(), ui_->imageView_source->isMirrorView(), this);
787  }
788  else
789  {
790  dialog = new AddObjectDialog(0, sceneImage_, ui_->imageView_source->isMirrorView(), this);
791  }
792  if(dialog->exec() == QDialog::Accepted)
793  {
794  ObjWidget * obj = 0;
795  ObjSignature * signature = 0;
796  dialog->retrieveObject(&obj, &signature);
797  UASSERT(obj!=0 && signature!=0);
798  findObject_->addObject(signature);
799  obj->setId(signature->id());
800  objWidgets_.insert(obj->id(), obj);
801  ui_->actionSave_objects->setEnabled(true);
802  ui_->actionSave_session->setEnabled(true);
803  showObject(obj);
804  QList<int> ids;
805  ids.push_back(obj->id());
806  updateVocabulary(ids);
807  objectsModified_ = true;
808  }
809  if(resumeCamera || sceneImage_.empty())
810  {
811  this->startProcessing();
812  }
813  else
814  {
815  connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
816  connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
817  if(!sceneImage_.empty())
818  {
819  this->update(sceneImage_);
820  }
821  }
822  delete dialog;
823 }
824 
825 void MainWindow::addObjectsFromFiles(const QStringList & fileNames)
826 {
827  if(fileNames.size())
828  {
829  QList<int> ids;
830  for(int i=0; i<fileNames.size(); ++i)
831  {
832  int id = this->addObjectFromFile(fileNames.at(i));
833  if(id >= 0)
834  {
835  ids.push_back(id);
836  }
837  }
838  if(ids.size())
839  {
840  objectsModified_ = true;
841  updateObjects(ids);
842  }
843  }
844 }
845 
847 {
848  addObjectsFromFiles(QFileDialog::getOpenFileNames(this, tr("Add objects..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats())));
849 }
850 
851 int MainWindow::addObjectFromFile(const QString & filePath)
852 {
853  const ObjSignature * s = findObject_->addObject(filePath);
854  if(s)
855  {
856  ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), QMultiMap<int,int>(), cvtCvMat2QImage(s->image()));
857  objWidgets_.insert(obj->id(), obj);
858  ui_->actionSave_objects->setEnabled(true);
859  ui_->actionSave_session->setEnabled(true);
860  this->showObject(obj);
861  return s->id();
862  }
863  else
864  {
865  QMessageBox::critical(this, tr("Error adding object"), tr("Failed to add object from \"%1\"").arg(filePath));
866  return -1;
867  }
868 }
869 
870 void MainWindow::addObjectFromTcp(const cv::Mat & image, int id, const QString & filePath)
871 {
872  if(objWidgets_.contains(id))
873  {
874  UERROR("Add Object: Object %d is already added.", id);
875  }
876  const ObjSignature * s = findObject_->addObject(image, id, filePath);
877  if(s)
878  {
879  ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), QMultiMap<int,int>(), cvtCvMat2QImage(s->image()));
880  objWidgets_.insert(obj->id(), obj);
881  ui_->actionSave_objects->setEnabled(true);
882  ui_->actionSave_session->setEnabled(true);
883  this->showObject(obj);
884  QList<int> ids;
885  ids.push_back(obj->id());
886  updateObjects(ids);
887  }
888  else
889  {
890  UERROR("Add Object: Error adding object %d.", id);
891  }
892 }
893 
894 void MainWindow::loadSceneFromFile(const QStringList & fileNames)
895 {
896  //take the first
897  if(fileNames.size())
898  {
899  cv::Mat img = cv::imread(fileNames.first().toStdString().c_str());
900  if(!img.empty())
901  {
902  this->update(img);
903  ui_->label_timeRefreshRate->setVisible(false);
904  }
905  }
906 }
907 
909 {
910  QString fileName = QFileDialog::getOpenFileName(this, tr("Load scene..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats()));
911  if(!fileName.isEmpty())
912  {
913  cv::Mat img = cv::imread(fileName.toStdString().c_str());
914  if(!img.empty())
915  {
916  this->update(img);
917  ui_->label_timeRefreshRate->setVisible(false);
918  }
919  }
920 }
921 
923 {
924  if(!ui_->actionCamera_from_video_file->isChecked())
925  {
926  Settings::setCamera_5mediaPath("");
927  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
928  }
929  else
930  {
931  QString fileName = QFileDialog::getOpenFileName(this, tr("Setup camera from video file..."), Settings::workingDirectory(), tr("Video Files (%1)").arg(Settings::getGeneral_videoFormats()));
932  if(!fileName.isEmpty())
933  {
934  Settings::setCamera_6useTcpCamera(false);
935  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
936 
937  Settings::setCamera_5mediaPath(fileName);
938  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
939  if(camera_->isRunning())
940  {
941  this->stopProcessing();
942  this->startProcessing();
943  }
944  Settings::setGeneral_controlsShown(true);
945  ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
946  }
947  }
948  ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
949  ui_->actionCamera_from_directory_of_images->setChecked(false);
950  ui_->actionCamera_from_TCP_IP->setChecked(false);
951 }
952 
954 {
955  if(!ui_->actionCamera_from_directory_of_images->isChecked())
956  {
957  Settings::setCamera_5mediaPath("");
958  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
959  }
960  else
961  {
962  QString directory = QFileDialog::getExistingDirectory(this, tr("Setup camera from directory of images..."), Settings::workingDirectory());
963  if(!directory.isEmpty())
964  {
965  Settings::setCamera_6useTcpCamera(false);
966  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
967 
968  Settings::setCamera_5mediaPath(directory);
969  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
970  if(camera_->isRunning())
971  {
972  this->stopProcessing();
973  this->startProcessing();
974  }
975  Settings::setGeneral_controlsShown(true);
976  ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
977  }
978  }
979  ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
980  ui_->actionCamera_from_video_file->setChecked(false);
981  ui_->actionCamera_from_TCP_IP->setChecked(false);
982 }
983 
985 {
986  if(!ui_->actionCamera_from_TCP_IP->isChecked())
987  {
988  Settings::setCamera_6useTcpCamera(false);
989  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
990  }
991  else
992  {
993  bool ok;
994  int port = QInputDialog::getInt(this, tr("Server port..."), "Port: ", Settings::getCamera_8port(), 1, USHRT_MAX, 1, &ok);
995 
996  if(ok)
997  {
998  int queue = QInputDialog::getInt(this, tr("Queue size..."), "Images buffer size (0 means infinite): ", Settings::getCamera_9queueSize(), 0, 2147483647, 1, &ok);
999  if(ok)
1000  {
1001  Settings::setCamera_6useTcpCamera(true);
1002  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
1003  Settings::setCamera_8port(port);
1004  ui_->toolBox->updateParameter(Settings::kCamera_8port());
1005  Settings::setCamera_9queueSize(queue);
1006  ui_->toolBox->updateParameter(Settings::kCamera_9queueSize());
1007  if(camera_->isRunning())
1008  {
1009  this->stopProcessing();
1010  }
1011  this->startProcessing();
1012  }
1013  }
1014  }
1015  ui_->actionCamera_from_directory_of_images->setChecked(false);
1016  ui_->actionCamera_from_video_file->setChecked(false);
1017  ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
1018 }
1019 
1021 {
1022  if(obj)
1023  {
1024  obj->setGraphicsViewMode(false);
1025  obj->setMirrorView(ui_->imageView_source->isMirrorView());
1026  QList<ObjWidget*> objs = ui_->objects_area->findChildren<ObjWidget*>();
1027  QVBoxLayout * vLayout = new QVBoxLayout();
1028  ui_->toolBox->updateParameter(Settings::kGeneral_nextObjID());
1029 
1030  QLabel * title = new QLabel(QString("%1 (%2)").arg(obj->id()).arg(obj->keypoints().size()), this);
1031  QLabel * detectedLabel = new QLabel(this);
1032  title->setObjectName(QString("%1title").arg(obj->id()));
1033  detectedLabel->setObjectName(QString("%1detection").arg(obj->id()));
1034  QHBoxLayout * hLayout = new QHBoxLayout();
1035  hLayout->addWidget(title);
1036  hLayout->addStretch(1);
1037  hLayout->addStretch(1);
1038  hLayout->addWidget(detectedLabel);
1039  vLayout->addLayout(hLayout);
1040  vLayout->addWidget(obj);
1041  obj->setDeletable(true);
1042  connect(obj, SIGNAL(removalTriggered(find_object::ObjWidget*)), this, SLOT(removeObject(find_object::ObjWidget*)));
1043  connect(obj, SIGNAL(destroyed(QObject *)), title, SLOT(deleteLater()));
1044  connect(obj, SIGNAL(destroyed(QObject *)), detectedLabel, SLOT(deleteLater()));
1045  connect(obj, SIGNAL(destroyed(QObject *)), vLayout, SLOT(deleteLater()));
1046  ui_->verticalLayout_objects->insertLayout(ui_->verticalLayout_objects->count()-1, vLayout);
1047 
1048  QByteArray ba;
1049  QBuffer buffer(&ba);
1050  buffer.open(QIODevice::WriteOnly);
1051  obj->pixmap().scaledToWidth(128).save(&buffer, "JPEG"); // writes image into JPEG format
1052  imagesMap_.insert(obj->id(), ba);
1053 
1054  // update objects size slider
1055  int objectsPanelWidth = ui_->dockWidget_objects->width();
1056  if(objectsPanelWidth > 0 && (obj->pixmap().width()*ui_->horizontalSlider_objectsSize->value()) / 100 > objectsPanelWidth)
1057  {
1058  ui_->horizontalSlider_objectsSize->setValue((objectsPanelWidth * 100) / obj->pixmap().width());
1059  }
1060  else
1061  {
1062  updateObjectSize(obj);
1063  }
1064  }
1065 }
1066 
1068 {
1069  updateObjects(QList<int>());
1070 }
1071 
1072 void MainWindow::updateObjects(const QList<int> & ids)
1073 {
1074  if(objWidgets_.size())
1075  {
1076  this->statusBar()->showMessage(tr("Updating %1 objects...").arg(ids.size()==0?objWidgets_.size():ids.size()));
1077 
1078  findObject_->updateObjects(ids);
1079 
1080  QList<int> idsTmp = ids;
1081  if(idsTmp.size() == 0)
1082  {
1083  idsTmp = objWidgets_.keys();
1084  }
1085 
1086  QList<ObjSignature*> signatures = findObject_->objects().values();
1087  for(int i=0; i<signatures.size(); ++i)
1088  {
1089  if(idsTmp.contains(signatures[i]->id()))
1090  {
1091  objWidgets_.value(signatures[i]->id())->updateData(signatures[i]->keypoints());
1092 
1093  //update object labels
1094  QLabel * title = this->findChild<QLabel*>(QString("%1title").arg(signatures[i]->id()));
1095  title->setText(QString("%1 (%2)").arg(signatures[i]->id()).arg(QString::number(signatures[i]->keypoints().size())));
1096 
1097  QLabel * label = this->findChild<QLabel*>(QString("%1detection").arg(signatures[i]->id()));
1098  label->clear();
1099  }
1100  }
1101 
1102  updateVocabulary(ids);
1103 
1104  if(!camera_->isRunning() && !sceneImage_.empty())
1105  {
1106  this->update(sceneImage_);
1107  }
1108  this->statusBar()->clearMessage();
1109  }
1110 }
1111 
1112 void MainWindow::updateVocabulary(const QList<int> & ids)
1113 {
1114  this->statusBar()->showMessage(tr("Updating vocabulary..."));
1115 
1116  QTime time;
1117  time.start();
1119 
1120  QList<int> idsTmp = ids;
1121  if(idsTmp.size() == 0)
1122  {
1123  idsTmp = objWidgets_.keys();
1124  }
1125  QList<ObjSignature*> signatures = findObject_->objects().values();
1126  for(int i=0; i<signatures.size(); ++i)
1127  {
1128  if(idsTmp.contains(signatures[i]->id()))
1129  {
1130  objWidgets_.value(signatures[i]->id())->updateWords(signatures[i]->words());
1131  }
1132  }
1133 
1134  ui_->label_timeIndexing->setNum(time.elapsed());
1135  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
1136  if(ids.size() && findObject_->vocabulary()->size() == 0 && Settings::getGeneral_vocabularyFixed() && Settings::getGeneral_invertedSearch())
1137  {
1138  QMessageBox::warning(this, tr("Vocabulary update"), tr("\"General/VocabularyFixed=true\" and the "
1139  "vocabulary is empty. New features cannot be matched to any words in the vocabulary."));
1140  }
1142  this->statusBar()->clearMessage();
1143  ui_->dockWidget_objects->update();
1144 }
1145 
1147 {
1148  UINFO("Starting camera...");
1149  bool updateStatusMessage = this->statusBar()->currentMessage().isEmpty();
1150  if(updateStatusMessage)
1151  {
1152  this->statusBar()->showMessage(tr("Starting camera..."));
1153  }
1154  if(camera_->start())
1155  {
1156  connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
1157  connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
1158  ui_->actionStop_camera->setEnabled(true);
1159  ui_->actionPause_camera->setEnabled(true);
1160  ui_->actionStart_camera->setEnabled(false);
1161  ui_->actionLoad_scene_from_file->setEnabled(false);
1162  ui_->actionCamera_from_directory_of_images->setEnabled(false);
1163  ui_->actionCamera_from_video_file->setEnabled(false);
1164  ui_->actionCamera_from_TCP_IP->setEnabled(false);
1165  ui_->label_timeRefreshRate->setVisible(true);
1166 
1167  //update control bar
1168  ui_->pushButton_play->setVisible(false);
1169  ui_->pushButton_pause->setVisible(true);
1170  ui_->pushButton_stop->setEnabled(true);
1171  int totalFrames = camera_->getTotalFrames();
1172  if(totalFrames>0)
1173  {
1174  ui_->label_frame->setVisible(true);
1175  ui_->horizontalSlider_frames->setEnabled(true);
1176  ui_->horizontalSlider_frames->setMaximum(totalFrames-1);
1177  }
1178 
1179  //update camera port if TCP is used
1180  ui_->label_port_image->setText("-");
1181  if(Settings::getCamera_6useTcpCamera() && camera_->getPort())
1182  {
1183  ui_->label_port_image->setNum(camera_->getPort());
1184  }
1185 
1186  if(updateStatusMessage)
1187  {
1188  this->statusBar()->showMessage(tr("Camera started."), 2000);
1189  }
1190  }
1191  else
1192  {
1193  if(updateStatusMessage)
1194  {
1195  this->statusBar()->clearMessage();
1196  }
1197 
1198  if(Settings::getCamera_6useTcpCamera())
1199  {
1200  QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with port %1)").arg(Settings::getCamera_8port()));
1201  }
1202  else
1203  {
1204  QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_1deviceId()));
1205  }
1206  }
1207 }
1208 
1210 {
1211  if(camera_)
1212  {
1213  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
1214  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
1215  camera_->stop();
1216  }
1217  ui_->actionStop_camera->setEnabled(false);
1218  ui_->actionPause_camera->setEnabled(false);
1219  ui_->actionStart_camera->setEnabled(true);
1220  ui_->actionLoad_scene_from_file->setEnabled(true);
1221  ui_->actionCamera_from_directory_of_images->setEnabled(true);
1222  ui_->actionCamera_from_video_file->setEnabled(true);
1223  ui_->actionCamera_from_TCP_IP->setEnabled(true);
1224  ui_->pushButton_play->setVisible(true);
1225  ui_->pushButton_pause->setVisible(false);
1226  ui_->pushButton_stop->setEnabled(false);
1227  ui_->horizontalSlider_frames->setEnabled(false);
1228  ui_->horizontalSlider_frames->setValue(0);
1229  ui_->label_frame->setVisible(false);
1230  ui_->label_port_image->setText("-");
1231 }
1232 
1234 {
1235  ui_->actionStop_camera->setEnabled(true);
1236  ui_->actionPause_camera->setEnabled(true);
1237  ui_->actionStart_camera->setEnabled(false);
1238  if(camera_->isRunning())
1239  {
1240  ui_->pushButton_play->setVisible(true);
1241  ui_->pushButton_pause->setVisible(false);
1242  camera_->pause();
1243  }
1244  else
1245  {
1246  ui_->pushButton_play->setVisible(false);
1247  ui_->pushButton_pause->setVisible(true);
1248  camera_->start();
1249  }
1250 }
1251 
1253 {
1254  if(ui_->horizontalSlider_frames->isEnabled())
1255  {
1256  camera_->moveToFrame(frame);
1257  if(!camera_->isRunning())
1258  {
1259  camera_->takeImage();
1260  }
1261  }
1262 }
1263 
1265 {
1266  if(objId>=0 && Settings::getGeneral_autoScroll())
1267  {
1268  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(objId));
1269  if(label)
1270  {
1271  ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
1272  }
1273  }
1274 }
1275 
1276 void MainWindow::update(const cv::Mat & image)
1277 {
1278  if(image.empty())
1279  {
1280  UWARN("The image received is empty...");
1281  return;
1282  }
1283  sceneImage_ = image.clone();
1284 
1285  // reset objects color
1286  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
1287  {
1288  iter.value()->resetKptsColor();
1289  if(!Settings::getGeneral_invertedSearch())
1290  {
1291  iter.value()->resetKptsWordID();
1292  }
1293  }
1294 
1295  QTime guiRefreshTime;
1296 
1297  DetectionInfo info;
1298  if(findObject_->detect(sceneImage_, info))
1299  {
1300  guiRefreshTime.start();
1301  ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
1302  ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
1303  ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
1304  ui_->label_timeSubPix->setNum(info.timeStamps_.value(DetectionInfo::kTimeSubPixelRefining, 0));
1305  ui_->imageView_source->updateImage(cvtCvMat2QImage(sceneImage_));
1306  ui_->imageView_source->updateData(info.sceneKeypoints_, info.sceneWords_);
1307  if(!findObject_->vocabulary()->size())
1308  {
1309  ui_->label_timeIndexing->setNum(info.timeStamps_.value(DetectionInfo::kTimeIndexing, 0));
1310  }
1311  ui_->label_timeMatching->setNum(info.timeStamps_.value(DetectionInfo::kTimeMatching, 0));
1312  ui_->label_timeHomographies->setNum(info.timeStamps_.value(DetectionInfo::kTimeHomography, 0));
1313 
1314  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
1315 
1316  // Colorize features matched
1317  const QMap<int, QMultiMap<int, int> > & matches = info.matches_;
1318  QMap<int, int> scores;
1319  int maxScoreId = -1;
1320  int maxScore = 0;
1321  for(QMap<int, QMultiMap<int, int> >::const_iterator jter=matches.constBegin(); jter!=matches.end();++jter)
1322  {
1323  scores.insert(jter.key(), jter.value().size());
1324  if(maxScoreId == -1 || maxScore < jter.value().size())
1325  {
1326  maxScoreId = jter.key();
1327  maxScore = jter.value().size();
1328  }
1329 
1330  int id = jter.key();
1331  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1332  if(!Settings::getHomography_homographyComputed())
1333  {
1334  label->setText(QString("%1 matches").arg(jter.value().size()));
1335 
1336  ObjWidget * obj = objWidgets_.value(id);
1337  UASSERT(obj != 0);
1338 
1339  for(QMultiMap<int, int>::const_iterator iter = jter.value().constBegin(); iter!= jter.value().constEnd(); ++iter)
1340  {
1341  obj->setKptColor(iter.key(), obj->color());
1342  ui_->imageView_source->setKptColor(iter.value(), obj->color());
1343  if(!Settings::getGeneral_invertedSearch())
1344  {
1345  obj->setKptWordID(iter.key(), ui_->imageView_source->words().value(iter.value(), -1));
1346  }
1347  }
1348  }
1349  else if(!info.objDetected_.contains(id))
1350  {
1351  // Homography could not be computed...
1352  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1353  QMultiMap<int, int> rejectedInliers = info.rejectedInliers_.value(id);
1354  QMultiMap<int, int> rejectedOutliers = info.rejectedOutliers_.value(id);
1355  int rejectedCode = info.rejectedCodes_.value(id);
1356  if(rejectedCode == DetectionInfo::kRejectedLowMatches)
1357  {
1358  label->setText(QString("Too low matches (%1)").arg(jter.value().size()));
1359  }
1360  else if(rejectedCode == DetectionInfo::kRejectedAllInliers)
1361  {
1362  label->setText(QString("Ignored, all inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1363  }
1364  else if(rejectedCode == DetectionInfo::kRejectedNotValid)
1365  {
1366  label->setText(QString("Not valid homography (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1367  }
1368  else if(rejectedCode == DetectionInfo::kRejectedLowInliers)
1369  {
1370  label->setText(QString("Too low inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1371  }
1372  else if(rejectedCode == DetectionInfo::kRejectedCornersOutside)
1373  {
1374  label->setText(QString("Corners not visible (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1375  }
1376  else if(rejectedCode == DetectionInfo::kRejectedByAngle)
1377  {
1378  label->setText(QString("Angle too small (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1379  }
1380  }
1381  }
1382 
1383  if(info.objDetected_.size() && camera_->isRunning() && Settings::getGeneral_autoPauseOnDetection())
1384  {
1385  this->pauseProcessing();
1386  }
1387 
1388  // Add homography rectangles when homographies are computed
1389  int maxHomographyScoreId = -1;
1390  int maxHomographyScore = 0;
1391  QMultiMap<int, QMultiMap<int,int> >::const_iterator inliersIter = info.objDetectedInliers_.constBegin();
1392  QMultiMap<int, QMultiMap<int,int> >::const_iterator outliersIter = info.objDetectedOutliers_.constBegin();
1393  for(QMultiMap<int,QTransform>::iterator iter = info.objDetected_.begin();
1394  iter!=info.objDetected_.end();
1395  ++iter, ++inliersIter, ++outliersIter)
1396  {
1397  int id = iter.key();
1398 
1399  if(maxHomographyScoreId == -1 || maxHomographyScore < inliersIter.value().size())
1400  {
1401  maxHomographyScoreId = id;
1402  maxHomographyScore = inliersIter.value().size();
1403  }
1404 
1405  ObjWidget * obj = objWidgets_.value(id);
1406  UASSERT(obj != 0);
1407 
1408  // COLORIZE (should be done in the GUI thread)
1409  QTransform hTransform = iter.value();
1410 
1411  QRect rect = obj->pixmap().rect();
1412  // add rectangle
1413  QPen rectPen(obj->color());
1414  rectPen.setWidth(Settings::getHomography_rectBorderWidth());
1415  RectItem * rectItemScene = new RectItem(id, rect);
1416  connect(rectItemScene, SIGNAL(hovered(int)), this, SLOT(rectHovered(int)));
1417  rectItemScene->setPen(rectPen);
1418  rectItemScene->setTransform(hTransform);
1419  ui_->imageView_source->addRect(rectItemScene);
1420 
1421  QGraphicsRectItem * rectItemObj = new QGraphicsRectItem(rect);
1422  rectItemObj->setPen(rectPen);
1423  obj->addRect(rectItemObj);
1424 
1425  for(QMultiMap<int, int>::const_iterator iter = inliersIter.value().constBegin(); iter!= inliersIter.value().constEnd(); ++iter)
1426  {
1427  obj->setKptColor(iter.key(), obj->color());
1428  ui_->imageView_source->setKptColor(iter.value(), obj->color());
1429  if(!Settings::getGeneral_invertedSearch())
1430  {
1431  obj->setKptWordID(iter.key(), ui_->imageView_source->words().value(iter.value(), -1));
1432  }
1433  }
1434 
1435  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1436  if(info.objDetected_.count(id) > 1)
1437  {
1438  // if a homography is already found, set the objects count
1439  label->setText(QString("%1 objects found").arg(info.objDetected_.count(id)));
1440  }
1441  else
1442  {
1443  label->setText(QString("%1 in %2 out").arg(inliersIter.value().size()).arg(outliersIter.value().size()));
1444  }
1445  }
1446 
1447  // save screenshot of the detection
1448  if(info.objDetected_.size() && !Settings::getGeneral_autoScreenshotPath().isEmpty())
1449  {
1450  QDir dir(Settings::getGeneral_autoScreenshotPath());
1451  if(!dir.exists())
1452  {
1453  QMessageBox::warning(this, tr("Screenshot on detection"), tr("Directory \"%1\" doesn't "
1454  "exist, screenshot of the detection cannot be taken. Parameter \"%2\" is cleared.").arg(Settings::getGeneral_autoScreenshotPath()).arg(Settings::kGeneral_autoScreenshotPath()));
1455  Settings::setGeneral_autoScreenshotPath("");
1456  ui_->toolBox->updateParameter(Settings::kGeneral_autoScreenshotPath());
1457  }
1458  else
1459  {
1460  QString path = Settings::getGeneral_autoScreenshotPath() + QDir::separator() + (QDateTime::currentDateTime().toString("yyMMddhhmmsszzz") + ".jpg");
1461  if(!ui_->imageView_source->getSceneAsPixmap().save(path))
1462  {
1463  UDEBUG("Failed to save screenshot \"%s\"! (%s is set)", path.toStdString().c_str(), Settings::kGeneral_autoScreenshotPath().toStdString().c_str());
1464  }
1465  else
1466  {
1467  UINFO("Save screenshot \"%s\"! (%s is set)", path.toStdString().c_str(), Settings::kGeneral_autoScreenshotPath().toStdString().c_str());
1468  }
1469  }
1470  }
1471 
1472  //update likelihood plot
1473  UDEBUG("Set likelihood score curve values (%d)", scores.size());
1474  likelihoodCurve_->setData(scores, QMap<int, int>());
1475  QMap<int, int> inlierScores;
1476  for(QMap<int, int>::iterator iter=scores.begin(); iter!=scores.end(); ++iter)
1477  {
1478  QList<QMultiMap<int, int> > values = info.objDetectedInliers_.values(iter.key());
1479  int maxValue = 0;
1480  if(values.size())
1481  {
1482  maxValue = values[0].size();
1483  for(int i=1; i<values.size(); ++i)
1484  {
1485  if(maxValue < values[i].size())
1486  {
1487  maxValue = values[i].size();
1488  }
1489  }
1490  }
1491  inlierScores.insert(iter.key(), maxValue);
1492  }
1493  UDEBUG("Set inliers score curve values (%d)", inlierScores.size());
1494  inliersCurve_->setData(inlierScores, QMap<int, int>());
1495  if(ui_->likelihoodPlot->isVisible())
1496  {
1497  ui_->likelihoodPlot->update();
1498  }
1499 
1500  ui_->label_minMatchedDistance->setNum(info.minMatchedDistance_);
1501  ui_->label_maxMatchedDistance->setNum(info.maxMatchedDistance_);
1502 
1503  //Scroll objects slider to the best score
1504  if((maxScoreId>=0 || maxHomographyScoreId>=0) && Settings::getGeneral_autoScroll())
1505  {
1506  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(maxHomographyScoreId>=0?maxHomographyScoreId:maxScoreId));
1507  if(label)
1508  {
1509  ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
1510  }
1511  }
1512 
1513  // Emit homographies
1514  if(info.objDetected_.size() > 1)
1515  {
1516  UINFO("(%s) %d objects detected!",
1517  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1518  (int)info.objDetected_.size());
1519  }
1520  else if(info.objDetected_.size() == 1)
1521  {
1522  UINFO("(%s) Object %d detected!",
1523  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1524  (int)info.objDetected_.begin().key());
1525  }
1526  else if(Settings::getGeneral_sendNoObjDetectedEvents())
1527  {
1528  UINFO("(%s) No objects detected.",
1529  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
1530  }
1531 
1532  if(info.objDetected_.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
1533  {
1534  Q_EMIT objectsFound(info);
1535  }
1536  ui_->label_objectsDetected->setNum(info.objDetected_.size());
1537  }
1538  else
1539  {
1540  guiRefreshTime.start();
1541 
1542  if(findObject_->vocabulary()->size())
1543  {
1544  this->statusBar()->showMessage(tr("Cannot search, objects must be updated!"));
1545  }
1546  ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
1547  ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
1548  ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
1549  ui_->label_timeSubPix->setNum(info.timeStamps_.value(DetectionInfo::kTimeSubPixelRefining, 0));
1550  ui_->imageView_source->updateImage(cvtCvMat2QImage(sceneImage_));
1551  ui_->imageView_source->updateData(info.sceneKeypoints_, info.sceneWords_);
1552  }
1553 
1554 
1555  //Update object pictures
1556  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
1557  {
1558  iter.value()->update();
1559  }
1560 
1561  ui_->label_nfeatures->setNum((int)info.sceneKeypoints_.size());
1562  ui_->imageView_source->update();
1563 
1564  ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
1565 
1566  //update slider
1567  if(ui_->horizontalSlider_frames->isEnabled())
1568  {
1569  ui_->horizontalSlider_frames->blockSignals(true);
1570  ui_->horizontalSlider_frames->setValue(camera_->getCurrentFrameIndex()-1);
1571  ui_->label_frame->setNum(camera_->getCurrentFrameIndex()-1);
1572  ui_->horizontalSlider_frames->blockSignals(false);
1573  }
1574 
1575  ui_->label_timeTotal->setNum(info.timeStamps_.value(DetectionInfo::kTimeTotal, 0));
1576  int refreshRate = qRound(1000.0f/float(updateRate_.restart()));
1577  if(refreshRate > 0 && refreshRate < lowestRefreshRate_)
1578  {
1579  lowestRefreshRate_ = refreshRate;
1580  }
1581  // Refresh the label only after each 1000 ms
1582  if(refreshStartTime_.elapsed() > 1000)
1583  {
1584  if(Settings::getCamera_4imageRate()>0.0)
1585  {
1586  ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(Settings::getCamera_4imageRate())).arg(QString::number(lowestRefreshRate_)));
1587  }
1588  else
1589  {
1590  ui_->label_timeRefreshRate->setText(QString("(%2 Hz)").arg(QString::number(lowestRefreshRate_)));
1591  }
1592  lowestRefreshRate_ = 99;
1593  refreshStartTime_.start();
1594  }
1595 
1596  ui_->label_timeRefreshGUI->setNum(guiRefreshTime.elapsed());
1597 }
1598 
1599 void MainWindow::notifyParametersChanged(const QStringList & paramChanged)
1600 {
1601  //Selective update (to not update all objects for a simple camera's parameter modification)
1602  bool detectorDescriptorParamsChanged = false;
1603  bool nearestNeighborParamsChanged = false;
1604  bool parameterChanged = false;
1605  for(QStringList::const_iterator iter = paramChanged.begin(); iter!=paramChanged.end(); ++iter)
1606  {
1607  if(lastObjectsUpdateParameters_.value(*iter) != Settings::getParameter(*iter))
1608  {
1610  parameterChanged = true;
1611  UINFO("Parameter changed: %s -> \"%s\"", iter->toStdString().c_str(), Settings::getParameter(*iter).toString().toStdString().c_str());
1612 
1613  if(iter->contains("Feature2D"))
1614  {
1615  detectorDescriptorParamsChanged = true;
1616  }
1617  else if( (iter->contains("NearestNeighbor") && Settings::getGeneral_invertedSearch()) ||
1618  iter->compare(Settings::kGeneral_invertedSearch()) == 0 ||
1619  (iter->compare(Settings::kGeneral_vocabularyIncremental()) == 0 && Settings::getGeneral_invertedSearch()) ||
1620  (iter->compare(Settings::kGeneral_vocabularyFixed()) == 0 && Settings::getGeneral_invertedSearch()) ||
1621  (iter->compare(Settings::kGeneral_threads()) == 0 && !Settings::getGeneral_invertedSearch()) )
1622  {
1623  nearestNeighborParamsChanged = true;
1624  }
1625 
1626  if(iter->compare(Settings::kGeneral_port()) == 0 &&
1627  Settings::getGeneral_port() != ui_->label_port->text().toInt() &&
1628  Settings::getGeneral_port() != 0)
1629  {
1630  setupTCPServer();
1631  }
1632  }
1633  }
1634 
1635  if(detectorDescriptorParamsChanged)
1636  {
1637  //Re-init detector and extractor
1639  }
1640 
1641  if(Settings::getGeneral_autoUpdateObjects())
1642  {
1643  if(detectorDescriptorParamsChanged)
1644  {
1645  this->updateObjects();
1646  }
1647  else if(nearestNeighborParamsChanged)
1648  {
1649  this->updateVocabulary();
1650  }
1651  }
1652  else if(objWidgets_.size() && (detectorDescriptorParamsChanged || nearestNeighborParamsChanged))
1653  {
1654  this->statusBar()->showMessage(tr("A parameter has changed... \"Update objects\" may be required."));
1655  }
1656 
1657  if(parameterChanged &&
1658  !camera_->isRunning() &&
1659  !sceneImage_.empty() &&
1660  !(Settings::getGeneral_autoUpdateObjects() && detectorDescriptorParamsChanged)) // already done in updateObjects() above
1661  {
1662  this->update(sceneImage_);
1663  ui_->label_timeRefreshRate->setVisible(false);
1664  }
1665  ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && !UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
1666  ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
1667  ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
1668 
1669  if(Settings::getGeneral_debug())
1670  {
1671  ULogger::setPrintWhere(true);
1673  }
1674  else
1675  {
1676  ULogger::setPrintWhere(false);
1678  }
1679 }
1680 
1681 } // namespace find_object
d
void addObjectFromTcp(const cv::Mat &image, int id, const QString &filePath)
Definition: MainWindow.cpp:870
virtual void keyPressEvent(QKeyEvent *event)
Definition: MainWindow.cpp:321
void updateVocabulary(const QList< int > &ids=QList< int >())
const QColor & color() const
Definition: ObjWidget.h:80
quint16 getPort() const
Definition: TcpServer.cpp:73
void moveCameraFrame(int frame)
static QVariant getParameter(const QString &key)
Definition: Settings.h:328
f
std::vector< double > values
virtual void takeImage()
Definition: Camera.cpp:121
const std::list< std::string > & getFileNames() const
Definition: UDirectory.h:125
virtual bool start()
Definition: Camera.cpp:183
TcpServer * tcpServer_
Definition: MainWindow.h:144
XmlRpcServer s
virtual bool isRunning()
Definition: Camera.h:50
std::vector< cv::KeyPoint > sceneKeypoints_
Definition: DetectionInfo.h:80
void updateObjectSize(find_object::ObjWidget *obj)
Definition: MainWindow.cpp:730
const std::vector< cv::KeyPoint > keypoints() const
Definition: ObjWidget.h:81
const QMap< int, ObjSignature * > & objects() const
Definition: FindObject.h:87
QMultiMap< int, RejectedCode > rejectedCodes_
Definition: DetectionInfo.h:88
static void loadWindowSettings(QByteArray &windowGeometry, QByteArray &windowState, const QString &fileName=QString())
Definition: Settings.cpp:198
QMap< int, QMultiMap< int, int > > matches_
Definition: DetectionInfo.h:83
void setData(const QMap< int, int > &dataMap, const QMap< int, int > &weightsMap)
Definition: PdfPlot.cpp:121
static void setLevel(ULogger::Level level)
Definition: ULogger.h:301
void setPen(const QPen &pen)
Definition: UPlot.cpp:645
QHostAddress getHostAddress() const
Definition: TcpServer.cpp:49
void showObject(find_object::ObjWidget *obj)
#define UASSERT(condition)
static QString currentDetectorType()
Definition: Settings.cpp:1230
static const ParametersMap & getParameters()
Definition: Settings.h:323
QMap< int, QByteArray > imagesMap_
Definition: MainWindow.h:142
void updateVocabulary(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:889
void moveToFrame(int frame)
Definition: Camera.cpp:100
const cv::Mat & image() const
Definition: ObjSignature.h:66
void setSourceImageText(const QString &text)
Definition: MainWindow.cpp:355
void setDeletable(bool deletable)
Definition: ObjWidget.cpp:412
rtabmap::PdfPlotCurve * likelihoodCurve_
Definition: MainWindow.h:134
void removeObject(find_object::ObjWidget *object)
Definition: MainWindow.cpp:675
static void loadSettings(const QString &fileName=QString())
Definition: Settings.cpp:103
QMap< TimeStamp, float > timeStamps_
Definition: DetectionInfo.h:79
void setKptColor(int index, const QColor &color)
Definition: ObjWidget.cpp:341
QMap< QString, QVariant > lastObjectsUpdateParameters_
Definition: MainWindow.h:143
AboutDialog * aboutDialog_
Definition: MainWindow.h:136
bool loadVocabulary(const QString &filePath)
Definition: FindObject.cpp:162
QMultiMap< int, QTransform > objDetected_
Definition: DetectionInfo.h:71
FindObject * findObject_
Definition: MainWindow.h:133
void updateObjects(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:797
void notifyParametersChanged(const QStringList &param)
void addRect(QGraphicsRectItem *rect)
Definition: ObjWidget.cpp:372
QMap< QString, QVariant > ParametersMap
Definition: Settings.h:41
void update(const cv::Mat &image)
int getTotalFrames()
Definition: Camera.cpp:74
static QString currentDescriptorType()
Definition: Settings.cpp:1236
rtabmap::PdfPlotCurve * inliersCurve_
Definition: MainWindow.h:135
QMultiMap< int, QMultiMap< int, int > > rejectedInliers_
Definition: DetectionInfo.h:86
static void setPrintWhere(bool printWhere)
Definition: ULogger.h:271
void rectHovered(int objId)
void setKptWordID(int index, int wordId)
Definition: ObjWidget.cpp:363
QMultiMap< int, QMultiMap< int, int > > objDetectedInliers_
Definition: DetectionInfo.h:76
MainWindow(find_object::FindObject *findObject, find_object::Camera *camera=0, QWidget *parent=0)
Definition: MainWindow.cpp:82
void setMirrorView(bool on)
Definition: ObjWidget.cpp:218
static void saveWindowSettings(const QByteArray &windowGeometry, const QByteArray &windowState, const QString &fileName=QString())
Definition: Settings.cpp:252
static QString workingDirectory()
Definition: Settings.cpp:70
int addObjectFromFile(const QString &filePath)
Definition: MainWindow.cpp:851
void removeObject(int id)
Definition: FindObject.cpp:310
virtual void closeEvent(QCloseEvent *event)
Definition: MainWindow.cpp:290
const Vocabulary * vocabulary() const
Definition: FindObject.h:88
#define UDEBUG(...)
virtual void stop()
Definition: Camera.cpp:55
bool loadSession(const QString &path)
Definition: FindObject.cpp:77
int id() const
Definition: ObjWidget.h:79
bool saveSession(const QString &path)
Definition: FindObject.cpp:129
#define UERROR(...)
QMultiMap< int, int > sceneWords_
Definition: DetectionInfo.h:82
ULogger class and convenient macros.
#define UWARN(...)
QMultiMap< int, QMultiMap< int, int > > rejectedOutliers_
Definition: DetectionInfo.h:87
void setGraphicsViewMode(bool on)
Definition: ObjWidget.cpp:146
static bool exists(const std::string &dirPath)
Definition: UDirectory.cpp:238
Ui_mainWindow * ui_
Definition: MainWindow.h:131
void setupCameraFromImagesDirectory()
Definition: MainWindow.cpp:953
QMultiMap< int, QMultiMap< int, int > > objDetectedOutliers_
Definition: DetectionInfo.h:77
int getCurrentFrameIndex()
Definition: Camera.cpp:87
static void saveSettings(const QString &fileName=QString())
Definition: Settings.cpp:226
const QPixmap & pixmap() const
Definition: ObjWidget.h:83
const ObjSignature * addObject(const QString &filePath)
Definition: FindObject.cpp:227
FINDOBJECT_EXP QImage cvtCvMat2QImage(const cv::Mat &image, bool isBgr=true)
Definition: QtOpenCV.cpp:34
QMap< int, find_object::ObjWidget * > objWidgets_
Definition: MainWindow.h:137
bool detect(const cv::Mat &image, find_object::DetectionInfo &info) const
void objectsFound(const find_object::DetectionInfo &)
void retrieveObject(ObjWidget **widget, ObjSignature **signature)
bool saveVocabulary(const QString &filePath) const
Definition: FindObject.cpp:157
#define UINFO(...)


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 19:22:26