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  UINFO("Creating %d object widgets...", findObject_->objects().size());
248  // show objects already loaded in FindObject
249  int i=0;
250  for(QMap<int, ObjSignature *>::const_iterator iter = findObject_->objects().constBegin();
251  iter!=findObject_->objects().constEnd();
252  ++iter)
253  {
254  ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), iter.value()->words(), iter.value()->image().empty()?QImage():cvtCvMat2QImage(iter.value()->image()));
255  objWidgets_.insert(obj->id(), obj);
256  this->showObject(obj);
257  ++i;
258  if(i % 100 == 0)
259  {
260  UINFO("Created %d/%d widgets...", i, findObject_->objects().size());
261  }
262  }
263  UINFO("Creating %d object widgets... done!", findObject_->objects().size());
264  ui_->actionSave_objects->setEnabled(true);
265  ui_->actionSave_session->setEnabled(true);
266  }
267  if(findObject_->vocabulary()->size())
268  {
269  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
270  ui_->actionSave_session->setEnabled(true);
271  }
272 
273 
274  if(Settings::getGeneral_autoStartCamera())
275  {
276  // Set 1 msec to see state on the status bar.
277  QTimer::singleShot(1, this, SLOT(startProcessing()));
278  }
279 
280  //Setup drag and drop images
281  connect(ui_->imageDrop_objects, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(addObjectsFromFiles(const QStringList &)));
282  connect(ui_->imageDrop_scene, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(loadSceneFromFile(const QStringList &)));
283 
284  ui_->imageView_source->setFocus();
285 }
286 
288 {
289  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
290  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), this, SLOT(update(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)));
291  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
292  camera_->stop();
293  qDeleteAll(objWidgets_);
294  objWidgets_.clear();
295  delete ui_;
296  delete findObject_;
297 }
298 
299 void MainWindow::closeEvent(QCloseEvent * event)
300 {
301  bool quit = true;
302  this->stopProcessing();
303  if(objectsModified_ && this->isVisible() && objWidgets_.size())
304  {
305  int ret = QMessageBox::question(this, tr("Save new objects"), tr("Do you want to save added objects?"), QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
306  switch(ret)
307  {
308  case QMessageBox::Yes:
309  quit = this->saveObjects();
310  break;
311  case QMessageBox::Cancel:
312  quit = false;
313  break;
314  case QMessageBox::No:
315  default:
316  break;
317  }
318  }
319  if(quit)
320  {
321  Settings::saveWindowSettings(this->saveGeometry(), this->saveState());
322  event->accept();
323  }
324  else
325  {
326  event->ignore();
327  }
328 }
329 
330 void MainWindow::keyPressEvent(QKeyEvent *event)
331 {
332  //catch ctrl-s to save settings
333  if(event->key() == Qt::Key_Space)
334  {
335  if(ui_->actionStart_camera->isEnabled())
336  {
337  startProcessing();
338  }
339  else if(ui_->actionPause_camera->isEnabled())
340  {
341  pauseProcessing();
342  }
343  }
344 }
345 
347 {
348  if(tcpServer_)
349  {
350  tcpServer_->close();
351  delete tcpServer_;
352  }
353  tcpServer_ = new TcpServer(Settings::getGeneral_port(), this);
354  connect(this, SIGNAL(objectsFound(const find_object::DetectionInfo &, const find_object::Header &, const cv::Mat &, float)), tcpServer_, SLOT(publishDetectionInfo(find_object::DetectionInfo)));
355  ui_->label_ipAddress->setText(tcpServer_->getHostAddress().toString());
356  ui_->label_port->setNum(tcpServer_->getPort());
357  UINFO("Detection sent on port: %d (IP=%s)", tcpServer_->getPort(), tcpServer_->getHostAddress().toString().toStdString().c_str());
358 
359  //connect services
360  connect(tcpServer_, SIGNAL(addObject(const cv::Mat &, int, const QString &)), this, SLOT(addObjectFromTcp(const cv::Mat &, int, const QString &)));
361  connect(tcpServer_, SIGNAL(removeObject(int)), this, SLOT(removeObject(int)));
362 }
363 
364 void MainWindow::setSourceImageText(const QString & text)
365 {
366  ui_->imageView_source->setTextLabel(text);
367 }
368 
370 {
371  if(objWidgets_.size())
372  {
373  QMessageBox::StandardButton b = QMessageBox::question(this, tr("Loading session..."),
374  tr("There are some objects (%1) already loaded, they will be "
375  "deleted when loading the session. Do you want to continue?").arg(objWidgets_.size()),
376  QMessageBox::Yes | QMessageBox::No, QMessageBox::NoButton);
377  if(b != QMessageBox::Yes)
378  {
379  return;
380  }
381  }
382 
383  QString path = QFileDialog::getOpenFileName(this, tr("Load session..."), Settings::workingDirectory(), "*.bin");
384  if(!path.isEmpty())
385  {
386  qDeleteAll(objWidgets_);
387  objWidgets_.clear();
388  ui_->actionSave_objects->setEnabled(false);
390 
391  if(findObject_->loadSession(path))
392  {
393  //update parameters tool box
394  const ParametersMap & parameters = Settings::getParameters();
395  for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
396  {
397  ui_->toolBox->updateParameter(iter.key());
398  }
399 
400  //update object widgets
401  for(QMap<int, ObjSignature *>::const_iterator iter=findObject_->objects().constBegin(); iter!=findObject_->objects().constEnd();++iter)
402  {
403  if(iter.value())
404  {
405  ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), iter.value()->words(), cvtCvMat2QImage(iter.value()->image()));
406  objWidgets_.insert(obj->id(), obj);
407  ui_->actionSave_objects->setEnabled(true);
408  ui_->actionSave_session->setEnabled(true);
409  this->showObject(obj);
410 
411  //update object labels
412  QLabel * title = this->findChild<QLabel*>(QString("%1title").arg(iter.value()->id()));
413  title->setText(QString("%1 (%2)").arg(iter.value()->id()).arg(QString::number(iter.value()->keypoints().size())));
414  }
415 
416  }
417 
418  QMessageBox::information(this, tr("Session loaded!"), tr("Session \"%1\" successfully loaded (%2 objects, %3 vocabulary words)!").arg(path).arg(objWidgets_.size()).arg(findObject_->vocabulary()->size()));
419 
420  if(!camera_->isRunning() && !sceneImage_.empty())
421  {
422  this->update(sceneImage_);
423  }
424  }
425  }
426 }
428 {
429  QString path = QFileDialog::getSaveFileName(this, tr("Save session..."), Settings::workingDirectory(), "*.bin");
430  if(!path.isEmpty())
431  {
432  if(QFileInfo(path).suffix().compare("bin") != 0)
433  {
434  path.append(".bin");
435  }
436 
437  if(findObject_->saveSession(path))
438  {
439  QMessageBox::information(this, tr("Session saved!"), tr("Session \"%1\" successfully saved (%2 objects, %3 vocabulary words)!").arg(path).arg(objWidgets_.size()).arg(findObject_->vocabulary()->size()));
440  }
441  }
442 }
443 
445 {
446  QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), Settings::workingDirectory(), "*.ini");
447  if(!path.isEmpty())
448  {
449  if(QFileInfo(path).suffix().compare("ini") != 0)
450  {
451  path.append(".ini");
452  }
453  loadSettings(path);
454  }
455 }
457 {
458  QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), Settings::workingDirectory(), "*.ini");
459  if(!path.isEmpty())
460  {
461  if(QFileInfo(path).suffix().compare("ini") != 0)
462  {
463  path.append(".ini");
464  }
465  saveSettings(path);
466  }
467 }
468 
469 bool MainWindow::loadSettings(const QString & path)
470 {
471  if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
472  {
473  QByteArray geometry;
474  QByteArray state;
476  Settings::loadWindowSettings(geometry, state, path);
477  this->restoreGeometry(geometry);
478  this->restoreState(state);
479 
480  //update parameters tool box
481  const ParametersMap & parameters = Settings::getParameters();
482  for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
483  {
484  ui_->toolBox->updateParameter(iter.key());
485  }
486 
487  return true;
488  }
489  UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
490  return false;
491 }
492 
493 bool MainWindow::saveSettings(const QString & path) const
494 {
495  if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
496  {
498  Settings::saveWindowSettings(this->saveGeometry(), this->saveState(), path);
499  return true;
500  }
501  UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
502  return false;
503 }
504 
505 int MainWindow::loadObjects(const QString & dirPath, bool recursive)
506 {
507  QList<int> loadedObjects;
508  QString formats = Settings::getGeneral_imageFormats().remove('*').remove('.');
509 
510  QStringList paths;
511  paths.append(dirPath);
512 
513  while(paths.size())
514  {
515  QString currentDir = paths.front();
516  UDirectory dir(currentDir.toStdString(), formats.toStdString());
517  if(dir.isValid())
518  {
519  const std::list<std::string> & names = dir.getFileNames(); // sorted in natural order
520  for(std::list<std::string>::const_iterator iter=names.begin(); iter!=names.end(); ++iter)
521  {
522  int id = this->addObjectFromFile((currentDir.toStdString()+dir.separator()+*iter).c_str());
523  if(id >= 0)
524  {
525  loadedObjects.push_back(id);
526  }
527  }
528  }
529 
530  paths.pop_front();
531 
532  if(recursive)
533  {
534  QDir d(currentDir);
535  QStringList subDirs = d.entryList(QDir::AllDirs|QDir::NoDotAndDotDot, QDir::Name);
536  for(int i=subDirs.size()-1; i>=0; --i)
537  {
538  paths.prepend(currentDir + QDir::separator() + subDirs[i]);
539  }
540  }
541  }
542 
543  if(loadedObjects.size())
544  {
545  this->updateObjects(loadedObjects);
546  }
547 
548  return loadedObjects.size();
549 }
550 
551 int MainWindow::saveObjects(const QString & dirPath)
552 {
553  int count = 0;
554  QDir dir(dirPath);
555  if(dir.exists())
556  {
557  for(QMap<int, ObjWidget*>::const_iterator iter=objWidgets_.constBegin(); iter!=objWidgets_.constEnd(); ++iter)
558  {
559  if(iter.value()->pixmap().save(QString("%1/%2.png").arg(dirPath).arg(iter.key())))
560  {
561  ++count;
562  }
563  else
564  {
565  UERROR("Failed to save object %d", iter.key());
566  }
567  }
568  objectsModified_ = false;
569  }
570  return count;
571 }
572 
574 {
575  QString dirPath = QFileDialog::getExistingDirectory(this, tr("Loading objects... Select a directory."), Settings::workingDirectory());
576  if(!dirPath.isEmpty())
577  {
578  QDir d(dirPath);
579  bool recursive = false;
580  if(d.entryList(QDir::AllDirs | QDir::NoDotAndDotDot).size())
581  {
582  QMessageBox::StandardButton b = QMessageBox::question(
583  this,
584  tr("Loading objects..."),
585  tr("The current directory contains subdirectories. Load objects recursively?"),
586  QMessageBox::Yes|QMessageBox::No,
587  QMessageBox::No);
588  recursive = b == QMessageBox::Yes;
589  }
590 
591  int count = loadObjects(dirPath, recursive);
592  if(count)
593  {
594  QMessageBox::information(this, tr("Loading..."), tr("%1 objects loaded from \"%2\".").arg(count).arg(dirPath));
595  }
596  else
597  {
598  QMessageBox::information(this, tr("Loading..."), tr("No objects loaded from \"%1\"!").arg(dirPath));
599  }
600  }
601 }
603 {
604  QString dirPath = QFileDialog::getExistingDirectory(this, tr("Saving objects... Select a directory."), Settings::workingDirectory());
605  if(!dirPath.isEmpty())
606  {
607  int count = saveObjects(dirPath);
608  if(count)
609  {
610  QMessageBox::information(this, tr("Saving..."), tr("%1 objects saved to \"%2\".").arg(count).arg(dirPath));
611  }
612  else
613  {
614  QMessageBox::warning(this, tr("Saving..."), tr("No objects saved to %1!").arg(dirPath));
615  }
616  return count > 0;
617  }
618  return false;
619 }
620 
622 {
623  if(!Settings::getGeneral_vocabularyFixed() ||
624  !Settings::getGeneral_invertedSearch())
625  {
626  QMessageBox::StandardButton b = QMessageBox::question(this, tr("Load vocabulary..."),
627  tr("Parameters \"General/vocabularyFixed\" and \"General/invertedSearch\" should be enabled to load a vocabulary. "
628  "Do you want to enable them now?"),
629  QMessageBox::Cancel | QMessageBox::Yes);
630  if(b == QMessageBox::Yes)
631  {
632  Settings::setGeneral_vocabularyFixed(true);
633  Settings::setGeneral_invertedSearch(true);
634  }
635  }
636  if(Settings::getGeneral_vocabularyFixed() &&
637  Settings::getGeneral_invertedSearch())
638  {
639  QString path = QFileDialog::getOpenFileName(this, tr("Load vocabulary..."), Settings::workingDirectory(), "Data (*.yaml *.xml *.bin)");
640  if(!path.isEmpty())
641  {
642  if(findObject_->loadVocabulary(path))
643  {
644  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
645  ui_->actionSave_session->setEnabled(findObject_->vocabulary()->size() || findObject_->objects().size());
646  QMessageBox::information(this, tr("Loading..."), tr("Vocabulary loaded from \"%1\" (%2 words).").arg(path).arg(findObject_->vocabulary()->size()));
647  }
648  else
649  {
650  QMessageBox::warning(this, tr("Loading..."), tr("Failed to load vocabulary \"%1\"!").arg(path));
651  }
652  }
653  }
654 }
655 
657 {
658  if(findObject_->vocabulary()->size() == 0)
659  {
660  QMessageBox::warning(this, tr("Saving vocabulary..."), tr("Vocabulary is empty!"));
661  return;
662  }
663  QString path = QFileDialog::getSaveFileName(this, tr("Save vocabulary..."), Settings::workingDirectory(), "Data (*.yaml *.xml *.bin)");
664  if(!path.isEmpty())
665  {
666  if( QFileInfo(path).suffix().compare("yaml") != 0 &&
667  QFileInfo(path).suffix().compare("xml") != 0 &&
668  QFileInfo(path).suffix().compare("bin") != 0)
669  {
670  path.append(".yaml");
671  }
672  if(findObject_->saveVocabulary(path))
673  {
674  QMessageBox::information(this, tr("Saving..."), tr("Vocabulary saved to \"%1\" (%2 words).").arg(path).arg(findObject_->vocabulary()->size()));
675  }
676  else
677  {
678  QMessageBox::warning(this, tr("Saving..."), tr("Failed to save vocabulary \"%1\"!").arg(path));
679  }
680  }
681 }
682 
684 {
685  if(object)
686  {
687  objWidgets_.remove(object->id());
688  if(objWidgets_.size() == 0)
689  {
690  ui_->actionSave_objects->setEnabled(false);
691  ui_->actionSave_session->setEnabled(false);
692  }
693  findObject_->removeObject(object->id());
694  object->deleteLater();
695  if(Settings::getGeneral_autoUpdateObjects())
696  {
697  this->updateVocabulary();
698  }
699  if(!camera_->isRunning() && !sceneImage_.empty())
700  {
701  this->update(sceneImage_);
702  }
703  }
704 }
705 
707 {
708  if(objWidgets_.contains(id))
709  {
711  }
712  else
713  {
714  UERROR("Remove object: Object %d not found!", id);
715  }
716 }
717 
719 {
720  qDeleteAll(objWidgets_);
721  objWidgets_.clear();
722  ui_->actionSave_objects->setEnabled(false);
724  if(!camera_->isRunning() && !sceneImage_.empty())
725  {
726  this->update(sceneImage_);
727  }
728 }
729 
731 {
732  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
733  {
734  updateObjectSize(iter.value());
735  }
736 }
737 
739 {
740  if(obj)
741  {
742  int value = ui_->horizontalSlider_objectsSize->value();
743  if((obj->pixmap().width()*value)/100 > 4 && (obj->pixmap().height()*value)/100 > 4)
744  {
745  obj->setVisible(true);
746  obj->setMinimumSize((obj->pixmap().width()*value)/100, (obj->pixmap().height())*value/100);
747  }
748  else
749  {
750  obj->setVisible(false);
751  }
752  }
753 }
754 
756 {
757  bool mirrorView = Settings::getGeneral_mirrorView();
758  ui_->imageView_source->setMirrorView(mirrorView);
759  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
760  {
761  iter.value()->setMirrorView(mirrorView);
762  }
763 }
764 
766 {
767  ui_->widget_controls->setVisible(Settings::getGeneral_controlsShown());
768 }
769 
771 {
772  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
773  {
774  iter.value()->setFeaturesShown(true);
775  }
776 }
777 
779 {
780  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
781  {
782  iter.value()->setFeaturesShown(false);
783  }
784 }
785 
787 {
788  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
789  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), this, SLOT(update(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)));
790  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
791  AddObjectDialog * dialog;
792  bool resumeCamera = camera_->isRunning();
793  if(camera_->isRunning() || sceneImage_.empty())
794  {
795  dialog = new AddObjectDialog(camera_, cv::Mat(), ui_->imageView_source->isMirrorView(), this);
796  }
797  else
798  {
799  dialog = new AddObjectDialog(0, sceneImage_, ui_->imageView_source->isMirrorView(), this);
800  }
801  if(dialog->exec() == QDialog::Accepted)
802  {
803  ObjWidget * obj = 0;
804  ObjSignature * signature = 0;
805  dialog->retrieveObject(&obj, &signature);
806  UASSERT(obj!=0 && signature!=0);
807  findObject_->addObject(signature);
808  obj->setId(signature->id());
809  objWidgets_.insert(obj->id(), obj);
810  ui_->actionSave_objects->setEnabled(true);
811  ui_->actionSave_session->setEnabled(true);
812  showObject(obj);
813  QList<int> ids;
814  ids.push_back(obj->id());
815  updateVocabulary(ids);
816  objectsModified_ = true;
817  }
818  if(resumeCamera || sceneImage_.empty())
819  {
820  this->startProcessing();
821  }
822  else
823  {
824  connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
825  connect(camera_, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), this, SLOT(update(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), Qt::UniqueConnection);
826  connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
827  if(!sceneImage_.empty())
828  {
829  this->update(sceneImage_);
830  }
831  }
832  delete dialog;
833 }
834 
835 void MainWindow::addObjectsFromFiles(const QStringList & fileNames)
836 {
837  if(fileNames.size())
838  {
839  QList<int> ids;
840  for(int i=0; i<fileNames.size(); ++i)
841  {
842  int id = this->addObjectFromFile(fileNames.at(i));
843  if(id >= 0)
844  {
845  ids.push_back(id);
846  }
847  }
848  if(ids.size())
849  {
850  objectsModified_ = true;
851  updateObjects(ids);
852  }
853  }
854 }
855 
857 {
858  addObjectsFromFiles(QFileDialog::getOpenFileNames(this, tr("Add objects..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats())));
859 }
860 
861 int MainWindow::addObjectFromFile(const QString & filePath)
862 {
863  const ObjSignature * s = findObject_->addObject(filePath);
864  if(s)
865  {
866  ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), QMultiMap<int,int>(), cvtCvMat2QImage(s->image()));
867  objWidgets_.insert(obj->id(), obj);
868  ui_->actionSave_objects->setEnabled(true);
869  ui_->actionSave_session->setEnabled(true);
870  this->showObject(obj);
871  return s->id();
872  }
873  else
874  {
875  QMessageBox::critical(this, tr("Error adding object"), tr("Failed to add object from \"%1\"").arg(filePath));
876  return -1;
877  }
878 }
879 
880 void MainWindow::addObjectFromTcp(const cv::Mat & image, int id, const QString & filePath)
881 {
882  if(objWidgets_.contains(id))
883  {
884  UERROR("Add Object: Object %d is already added.", id);
885  }
886  const ObjSignature * s = findObject_->addObject(image, id, filePath);
887  if(s)
888  {
889  ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), QMultiMap<int,int>(), cvtCvMat2QImage(s->image()));
890  objWidgets_.insert(obj->id(), obj);
891  ui_->actionSave_objects->setEnabled(true);
892  ui_->actionSave_session->setEnabled(true);
893  this->showObject(obj);
894  QList<int> ids;
895  ids.push_back(obj->id());
896  updateObjects(ids);
897  }
898  else
899  {
900  UERROR("Add Object: Error adding object %d.", id);
901  }
902 }
903 
904 void MainWindow::loadSceneFromFile(const QStringList & fileNames)
905 {
906  //take the first
907  if(fileNames.size())
908  {
909  cv::Mat img = cv::imread(fileNames.first().toStdString().c_str());
910  if(!img.empty())
911  {
912  this->update(img);
913  ui_->label_timeRefreshRate->setVisible(false);
914  }
915  }
916 }
917 
919 {
920  QString fileName = QFileDialog::getOpenFileName(this, tr("Load scene..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats()));
921  if(!fileName.isEmpty())
922  {
923  cv::Mat img = cv::imread(fileName.toStdString().c_str());
924  if(!img.empty())
925  {
926  this->update(img);
927  ui_->label_timeRefreshRate->setVisible(false);
928  }
929  }
930 }
931 
933 {
934  if(!ui_->actionCamera_from_video_file->isChecked())
935  {
936  Settings::setCamera_5mediaPath("");
937  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
938  }
939  else
940  {
941  QString fileName = QFileDialog::getOpenFileName(this, tr("Setup camera from video file..."), Settings::workingDirectory(), tr("Video Files (%1)").arg(Settings::getGeneral_videoFormats()));
942  if(!fileName.isEmpty())
943  {
944  Settings::setCamera_6useTcpCamera(false);
945  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
946 
947  Settings::setCamera_5mediaPath(fileName);
948  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
949  if(camera_->isRunning())
950  {
951  this->stopProcessing();
952  this->startProcessing();
953  }
954  Settings::setGeneral_controlsShown(true);
955  ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
956  }
957  }
958  ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
959  ui_->actionCamera_from_directory_of_images->setChecked(false);
960  ui_->actionCamera_from_TCP_IP->setChecked(false);
961 }
962 
964 {
965  if(!ui_->actionCamera_from_directory_of_images->isChecked())
966  {
967  Settings::setCamera_5mediaPath("");
968  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
969  }
970  else
971  {
972  QString directory = QFileDialog::getExistingDirectory(this, tr("Setup camera from directory of images..."), Settings::workingDirectory());
973  if(!directory.isEmpty())
974  {
975  Settings::setCamera_6useTcpCamera(false);
976  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
977 
978  Settings::setCamera_5mediaPath(directory);
979  ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
980  if(camera_->isRunning())
981  {
982  this->stopProcessing();
983  this->startProcessing();
984  }
985  Settings::setGeneral_controlsShown(true);
986  ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
987  }
988  }
989  ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
990  ui_->actionCamera_from_video_file->setChecked(false);
991  ui_->actionCamera_from_TCP_IP->setChecked(false);
992 }
993 
995 {
996  if(!ui_->actionCamera_from_TCP_IP->isChecked())
997  {
998  Settings::setCamera_6useTcpCamera(false);
999  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
1000  }
1001  else
1002  {
1003  bool ok;
1004  int port = QInputDialog::getInt(this, tr("Server port..."), "Port: ", Settings::getCamera_8port(), 1, USHRT_MAX, 1, &ok);
1005 
1006  if(ok)
1007  {
1008  int queue = QInputDialog::getInt(this, tr("Queue size..."), "Images buffer size (0 means infinite): ", Settings::getCamera_9queueSize(), 0, 2147483647, 1, &ok);
1009  if(ok)
1010  {
1011  Settings::setCamera_6useTcpCamera(true);
1012  ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
1013  Settings::setCamera_8port(port);
1014  ui_->toolBox->updateParameter(Settings::kCamera_8port());
1015  Settings::setCamera_9queueSize(queue);
1016  ui_->toolBox->updateParameter(Settings::kCamera_9queueSize());
1017  if(camera_->isRunning())
1018  {
1019  this->stopProcessing();
1020  }
1021  this->startProcessing();
1022  }
1023  }
1024  }
1025  ui_->actionCamera_from_directory_of_images->setChecked(false);
1026  ui_->actionCamera_from_video_file->setChecked(false);
1027  ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
1028 }
1029 
1031 {
1032  if(obj)
1033  {
1034  obj->setGraphicsViewMode(false);
1035  obj->setMirrorView(ui_->imageView_source->isMirrorView());
1036  QList<ObjWidget*> objs = ui_->objects_area->findChildren<ObjWidget*>();
1037  QVBoxLayout * vLayout = new QVBoxLayout();
1038  ui_->toolBox->updateParameter(Settings::kGeneral_nextObjID());
1039 
1040  QLabel * title = new QLabel(QString("%1 (%2)").arg(obj->id()).arg(obj->keypoints().size()), this);
1041  QLabel * detectedLabel = new QLabel(this);
1042  title->setObjectName(QString("%1title").arg(obj->id()));
1043  detectedLabel->setObjectName(QString("%1detection").arg(obj->id()));
1044  QHBoxLayout * hLayout = new QHBoxLayout();
1045  hLayout->addWidget(title);
1046  hLayout->addStretch(1);
1047  hLayout->addStretch(1);
1048  hLayout->addWidget(detectedLabel);
1049  vLayout->addLayout(hLayout);
1050  vLayout->addWidget(obj);
1051  obj->setDeletable(true);
1052  connect(obj, SIGNAL(removalTriggered(find_object::ObjWidget*)), this, SLOT(removeObject(find_object::ObjWidget*)));
1053  connect(obj, SIGNAL(destroyed(QObject *)), title, SLOT(deleteLater()));
1054  connect(obj, SIGNAL(destroyed(QObject *)), detectedLabel, SLOT(deleteLater()));
1055  connect(obj, SIGNAL(destroyed(QObject *)), vLayout, SLOT(deleteLater()));
1056  ui_->verticalLayout_objects->insertLayout(ui_->verticalLayout_objects->count()-1, vLayout);
1057 
1058  QByteArray ba;
1059  if(obj->pixmap().width() > 0)
1060  {
1061  QBuffer buffer(&ba);
1062  buffer.open(QIODevice::WriteOnly);
1063  obj->pixmap().scaledToWidth(128).save(&buffer, "JPEG"); // writes image into JPEG format
1064  }
1065  imagesMap_.insert(obj->id(), ba);
1066 
1067  // update objects size slider
1068  int objectsPanelWidth = ui_->dockWidget_objects->width();
1069  if(objectsPanelWidth > 0 && (obj->pixmap().width()*ui_->horizontalSlider_objectsSize->value()) / 100 > objectsPanelWidth)
1070  {
1071  ui_->horizontalSlider_objectsSize->setValue((objectsPanelWidth * 100) / obj->pixmap().width());
1072  }
1073  else
1074  {
1075  updateObjectSize(obj);
1076  }
1077  }
1078 }
1079 
1081 {
1082  updateObjects(QList<int>());
1083 }
1084 
1085 void MainWindow::updateObjects(const QList<int> & ids)
1086 {
1087  if(objWidgets_.size())
1088  {
1089  this->statusBar()->showMessage(tr("Updating %1 objects...").arg(ids.size()==0?objWidgets_.size():ids.size()));
1090 
1091  findObject_->updateObjects(ids);
1092 
1093  QList<int> idsTmp = ids;
1094  if(idsTmp.size() == 0)
1095  {
1096  idsTmp = objWidgets_.keys();
1097  }
1098 
1099  QList<ObjSignature*> signatures = findObject_->objects().values();
1100  for(int i=0; i<signatures.size(); ++i)
1101  {
1102  if(idsTmp.contains(signatures[i]->id()))
1103  {
1104  objWidgets_.value(signatures[i]->id())->updateData(signatures[i]->keypoints());
1105 
1106  //update object labels
1107  QLabel * title = this->findChild<QLabel*>(QString("%1title").arg(signatures[i]->id()));
1108  title->setText(QString("%1 (%2)").arg(signatures[i]->id()).arg(QString::number(signatures[i]->keypoints().size())));
1109 
1110  QLabel * label = this->findChild<QLabel*>(QString("%1detection").arg(signatures[i]->id()));
1111  label->clear();
1112  }
1113  }
1114 
1115  updateVocabulary(ids);
1116 
1117  if(!camera_->isRunning() && !sceneImage_.empty())
1118  {
1119  this->update(sceneImage_);
1120  }
1121  this->statusBar()->clearMessage();
1122  }
1123 }
1124 
1125 void MainWindow::updateVocabulary(const QList<int> & ids)
1126 {
1127  this->statusBar()->showMessage(tr("Updating vocabulary..."));
1128 
1129  QTime time;
1130  time.start();
1132 
1133  QList<int> idsTmp = ids;
1134  if(idsTmp.size() == 0)
1135  {
1136  idsTmp = objWidgets_.keys();
1137  }
1138  QList<ObjSignature*> signatures = findObject_->objects().values();
1139  for(int i=0; i<signatures.size(); ++i)
1140  {
1141  if(idsTmp.contains(signatures[i]->id()))
1142  {
1143  objWidgets_.value(signatures[i]->id())->updateWords(signatures[i]->words());
1144  }
1145  }
1146 
1147  ui_->label_timeIndexing->setNum(time.elapsed());
1148  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
1149  if(ids.size() && findObject_->vocabulary()->size() == 0 && Settings::getGeneral_vocabularyFixed() && Settings::getGeneral_invertedSearch())
1150  {
1151  QMessageBox::warning(this, tr("Vocabulary update"), tr("\"General/VocabularyFixed=true\" and the "
1152  "vocabulary is empty. New features cannot be matched to any words in the vocabulary."));
1153  }
1155  this->statusBar()->clearMessage();
1156  ui_->dockWidget_objects->update();
1157 }
1158 
1160 {
1161  UINFO("Starting camera...");
1162  bool updateStatusMessage = this->statusBar()->currentMessage().isEmpty();
1163  if(updateStatusMessage)
1164  {
1165  this->statusBar()->showMessage(tr("Starting camera..."));
1166  }
1167  if(camera_->start())
1168  {
1169  connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
1170  connect(camera_, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), this, SLOT(update(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), Qt::UniqueConnection);
1171  connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
1172  ui_->actionStop_camera->setEnabled(true);
1173  ui_->actionPause_camera->setEnabled(true);
1174  ui_->actionStart_camera->setEnabled(false);
1175  ui_->actionLoad_scene_from_file->setEnabled(false);
1176  ui_->actionCamera_from_directory_of_images->setEnabled(false);
1177  ui_->actionCamera_from_video_file->setEnabled(false);
1178  ui_->actionCamera_from_TCP_IP->setEnabled(false);
1179  ui_->label_timeRefreshRate->setVisible(true);
1180 
1181  //update control bar
1182  ui_->pushButton_play->setVisible(false);
1183  ui_->pushButton_pause->setVisible(true);
1184  ui_->pushButton_stop->setEnabled(true);
1185  int totalFrames = camera_->getTotalFrames();
1186  if(totalFrames>0)
1187  {
1188  ui_->label_frame->setVisible(true);
1189  ui_->horizontalSlider_frames->setEnabled(true);
1190  ui_->horizontalSlider_frames->setMaximum(totalFrames-1);
1191  }
1192 
1193  //update camera port if TCP is used
1194  ui_->label_port_image->setText("-");
1195  if(Settings::getCamera_6useTcpCamera() && camera_->getPort())
1196  {
1197  ui_->label_port_image->setNum(camera_->getPort());
1198  }
1199 
1200  if(updateStatusMessage)
1201  {
1202  this->statusBar()->showMessage(tr("Camera started."), 2000);
1203  }
1204  }
1205  else
1206  {
1207  if(updateStatusMessage)
1208  {
1209  this->statusBar()->clearMessage();
1210  }
1211 
1212  if(Settings::getCamera_6useTcpCamera())
1213  {
1214  QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with port %1)").arg(Settings::getCamera_8port()));
1215  }
1216  else
1217  {
1218  QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_1deviceId()));
1219  }
1220  }
1221 }
1222 
1224 {
1225  if(camera_)
1226  {
1227  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
1228  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)), this, SLOT(update(const cv::Mat &, const find_object::Header &, const cv::Mat &, float)));
1229  disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
1230  camera_->stop();
1231  }
1232  ui_->actionStop_camera->setEnabled(false);
1233  ui_->actionPause_camera->setEnabled(false);
1234  ui_->actionStart_camera->setEnabled(true);
1235  ui_->actionLoad_scene_from_file->setEnabled(true);
1236  ui_->actionCamera_from_directory_of_images->setEnabled(true);
1237  ui_->actionCamera_from_video_file->setEnabled(true);
1238  ui_->actionCamera_from_TCP_IP->setEnabled(true);
1239  ui_->pushButton_play->setVisible(true);
1240  ui_->pushButton_pause->setVisible(false);
1241  ui_->pushButton_stop->setEnabled(false);
1242  ui_->horizontalSlider_frames->setEnabled(false);
1243  ui_->horizontalSlider_frames->setValue(0);
1244  ui_->label_frame->setVisible(false);
1245  ui_->label_port_image->setText("-");
1246 }
1247 
1249 {
1250  ui_->actionStop_camera->setEnabled(true);
1251  ui_->actionPause_camera->setEnabled(true);
1252  ui_->actionStart_camera->setEnabled(false);
1253  if(camera_->isRunning())
1254  {
1255  ui_->pushButton_play->setVisible(true);
1256  ui_->pushButton_pause->setVisible(false);
1257  camera_->pause();
1258  }
1259  else
1260  {
1261  ui_->pushButton_play->setVisible(false);
1262  ui_->pushButton_pause->setVisible(true);
1263  camera_->start();
1264  }
1265 }
1266 
1268 {
1269  if(ui_->horizontalSlider_frames->isEnabled())
1270  {
1271  camera_->moveToFrame(frame);
1272  if(!camera_->isRunning())
1273  {
1274  camera_->takeImage();
1275  }
1276  }
1277 }
1278 
1280 {
1281  if(objId>=0 && Settings::getGeneral_autoScroll())
1282  {
1283  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(objId));
1284  if(label)
1285  {
1286  ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
1287  }
1288  }
1289 }
1290 
1291 void MainWindow::update(const cv::Mat & image)
1292 {
1293  update(image, Header(), cv::Mat(), 0.0);
1294 }
1295 
1296 void MainWindow::update(const cv::Mat & image, const Header & header, const cv::Mat & depth, float depthConstant)
1297 {
1298  if(image.empty())
1299  {
1300  UWARN("The image received is empty...");
1301  return;
1302  }
1303  sceneImage_ = image.clone();
1304 
1305  // reset objects color
1306  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
1307  {
1308  iter.value()->resetKptsColor();
1309  if(!Settings::getGeneral_invertedSearch())
1310  {
1311  iter.value()->resetKptsWordID();
1312  }
1313  }
1314 
1315  QTime guiRefreshTime;
1316 
1317  DetectionInfo info;
1318  if(findObject_->detect(sceneImage_, info))
1319  {
1320  guiRefreshTime.start();
1321  ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
1322  ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
1323  ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
1324  ui_->label_timeSubPix->setNum(info.timeStamps_.value(DetectionInfo::kTimeSubPixelRefining, 0));
1325  ui_->imageView_source->updateImage(cvtCvMat2QImage(sceneImage_));
1326  ui_->imageView_source->updateData(info.sceneKeypoints_, info.sceneWords_);
1327  if(!findObject_->vocabulary()->size())
1328  {
1329  ui_->label_timeIndexing->setNum(info.timeStamps_.value(DetectionInfo::kTimeIndexing, 0));
1330  }
1331  ui_->label_timeMatching->setNum(info.timeStamps_.value(DetectionInfo::kTimeMatching, 0));
1332  ui_->label_timeHomographies->setNum(info.timeStamps_.value(DetectionInfo::kTimeHomography, 0));
1333 
1334  ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
1335 
1336  // Colorize features matched
1337  const QMap<int, QMultiMap<int, int> > & matches = info.matches_;
1338  QMap<int, int> scores;
1339  int maxScoreId = -1;
1340  int maxScore = 0;
1341  for(QMap<int, QMultiMap<int, int> >::const_iterator jter=matches.constBegin(); jter!=matches.end();++jter)
1342  {
1343  scores.insert(jter.key(), jter.value().size());
1344  if(maxScoreId == -1 || maxScore < jter.value().size())
1345  {
1346  maxScoreId = jter.key();
1347  maxScore = jter.value().size();
1348  }
1349 
1350  int id = jter.key();
1351  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1352  if(!Settings::getHomography_homographyComputed())
1353  {
1354  label->setText(QString("%1 matches").arg(jter.value().size()));
1355 
1356  ObjWidget * obj = objWidgets_.value(id);
1357  UASSERT(obj != 0);
1358 
1359  for(QMultiMap<int, int>::const_iterator iter = jter.value().constBegin(); iter!= jter.value().constEnd(); ++iter)
1360  {
1361  obj->setKptColor(iter.key(), obj->color());
1362  ui_->imageView_source->setKptColor(iter.value(), obj->color());
1363  if(!Settings::getGeneral_invertedSearch())
1364  {
1365  obj->setKptWordID(iter.key(), ui_->imageView_source->words().value(iter.value(), -1));
1366  }
1367  }
1368  }
1369  else if(!info.objDetected_.contains(id))
1370  {
1371  // Homography could not be computed...
1372  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1373  QMultiMap<int, int> rejectedInliers = info.rejectedInliers_.value(id);
1374  QMultiMap<int, int> rejectedOutliers = info.rejectedOutliers_.value(id);
1375  int rejectedCode = info.rejectedCodes_.value(id);
1376  if(rejectedCode == DetectionInfo::kRejectedLowMatches)
1377  {
1378  label->setText(QString("Too low matches (%1)").arg(jter.value().size()));
1379  }
1380  else if(rejectedCode == DetectionInfo::kRejectedAllInliers)
1381  {
1382  label->setText(QString("Ignored, all inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1383  }
1384  else if(rejectedCode == DetectionInfo::kRejectedNotValid)
1385  {
1386  label->setText(QString("Not valid homography (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1387  }
1388  else if(rejectedCode == DetectionInfo::kRejectedLowInliers)
1389  {
1390  label->setText(QString("Too low inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1391  }
1392  else if(rejectedCode == DetectionInfo::kRejectedCornersOutside)
1393  {
1394  label->setText(QString("Corners not visible (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1395  }
1396  else if(rejectedCode == DetectionInfo::kRejectedByAngle)
1397  {
1398  label->setText(QString("Angle too small (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
1399  }
1400  }
1401  }
1402 
1403  if(info.objDetected_.size() && camera_->isRunning() && Settings::getGeneral_autoPauseOnDetection())
1404  {
1405  this->pauseProcessing();
1406  }
1407 
1408  // Add homography rectangles when homographies are computed
1409  int maxHomographyScoreId = -1;
1410  int maxHomographyScore = 0;
1411  QMultiMap<int, QMultiMap<int,int> >::const_iterator inliersIter = info.objDetectedInliers_.constBegin();
1412  QMultiMap<int, QMultiMap<int,int> >::const_iterator outliersIter = info.objDetectedOutliers_.constBegin();
1413  for(QMultiMap<int,QTransform>::iterator iter = info.objDetected_.begin();
1414  iter!=info.objDetected_.end();
1415  ++iter, ++inliersIter, ++outliersIter)
1416  {
1417  int id = iter.key();
1418 
1419  if(maxHomographyScoreId == -1 || maxHomographyScore < inliersIter.value().size())
1420  {
1421  maxHomographyScoreId = id;
1422  maxHomographyScore = inliersIter.value().size();
1423  }
1424 
1425  ObjWidget * obj = objWidgets_.value(id);
1426  UASSERT(obj != 0);
1427 
1428  // COLORIZE (should be done in the GUI thread)
1429  QTransform hTransform = iter.value();
1430 
1431  QRect rect = obj->pixmap().rect();
1432  // add rectangle
1433  QPen rectPen(obj->color());
1434  rectPen.setWidth(Settings::getHomography_rectBorderWidth());
1435  if(rect.isNull())
1436  {
1437  QMap<int, ObjSignature*>::const_iterator iter = findObject_->objects().constFind(id);
1438  if(iter!=findObject_->objects().end())
1439  {
1440  rect = iter.value()->rect();
1441  }
1442  }
1443  RectItem * rectItemScene = new RectItem(id, rect);
1444  connect(rectItemScene, SIGNAL(hovered(int)), this, SLOT(rectHovered(int)));
1445  rectItemScene->setPen(rectPen);
1446  rectItemScene->setTransform(hTransform);
1447  ui_->imageView_source->addRect(rectItemScene);
1448 
1449  QGraphicsRectItem * rectItemObj = new QGraphicsRectItem(rect);
1450  rectItemObj->setPen(rectPen);
1451  obj->addRect(rectItemObj);
1452 
1453  for(QMultiMap<int, int>::const_iterator iter = inliersIter.value().constBegin(); iter!= inliersIter.value().constEnd(); ++iter)
1454  {
1455  obj->setKptColor(iter.key(), obj->color());
1456  ui_->imageView_source->setKptColor(iter.value(), obj->color());
1457  if(!Settings::getGeneral_invertedSearch())
1458  {
1459  obj->setKptWordID(iter.key(), ui_->imageView_source->words().value(iter.value(), -1));
1460  }
1461  }
1462 
1463  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
1464  if(info.objDetected_.count(id) > 1)
1465  {
1466  // if a homography is already found, set the objects count
1467  label->setText(QString("%1 objects found").arg(info.objDetected_.count(id)));
1468  }
1469  else
1470  {
1471  label->setText(QString("%1 in %2 out").arg(inliersIter.value().size()).arg(outliersIter.value().size()));
1472  }
1473  }
1474 
1475  // save screenshot of the detection
1476  if(info.objDetected_.size() && !Settings::getGeneral_autoScreenshotPath().isEmpty())
1477  {
1478  QDir dir(Settings::getGeneral_autoScreenshotPath());
1479  if(!dir.exists())
1480  {
1481  QMessageBox::warning(this, tr("Screenshot on detection"), tr("Directory \"%1\" doesn't "
1482  "exist, screenshot of the detection cannot be taken. Parameter \"%2\" is cleared.").arg(Settings::getGeneral_autoScreenshotPath()).arg(Settings::kGeneral_autoScreenshotPath()));
1483  Settings::setGeneral_autoScreenshotPath("");
1484  ui_->toolBox->updateParameter(Settings::kGeneral_autoScreenshotPath());
1485  }
1486  else
1487  {
1488  QString path = Settings::getGeneral_autoScreenshotPath() + QDir::separator() + (QDateTime::currentDateTime().toString("yyMMddhhmmsszzz") + ".jpg");
1489  if(!ui_->imageView_source->getSceneAsPixmap().save(path))
1490  {
1491  UDEBUG("Failed to save screenshot \"%s\"! (%s is set)", path.toStdString().c_str(), Settings::kGeneral_autoScreenshotPath().toStdString().c_str());
1492  }
1493  else
1494  {
1495  UINFO("Save screenshot \"%s\"! (%s is set)", path.toStdString().c_str(), Settings::kGeneral_autoScreenshotPath().toStdString().c_str());
1496  }
1497  }
1498  }
1499 
1500  //update likelihood plot
1501  UDEBUG("Set likelihood score curve values (%d)", scores.size());
1502  likelihoodCurve_->setData(scores, QMap<int, int>());
1503  QMap<int, int> inlierScores;
1504  for(QMap<int, int>::iterator iter=scores.begin(); iter!=scores.end(); ++iter)
1505  {
1506  QList<QMultiMap<int, int> > values = info.objDetectedInliers_.values(iter.key());
1507  int maxValue = 0;
1508  if(values.size())
1509  {
1510  maxValue = values[0].size();
1511  for(int i=1; i<values.size(); ++i)
1512  {
1513  if(maxValue < values[i].size())
1514  {
1515  maxValue = values[i].size();
1516  }
1517  }
1518  }
1519  inlierScores.insert(iter.key(), maxValue);
1520  }
1521  UDEBUG("Set inliers score curve values (%d)", inlierScores.size());
1522  inliersCurve_->setData(inlierScores, QMap<int, int>());
1523  if(ui_->likelihoodPlot->isVisible())
1524  {
1525  ui_->likelihoodPlot->update();
1526  }
1527 
1528  ui_->label_minMatchedDistance->setNum(info.minMatchedDistance_);
1529  ui_->label_maxMatchedDistance->setNum(info.maxMatchedDistance_);
1530 
1531  //Scroll objects slider to the best score
1532  if((maxScoreId>=0 || maxHomographyScoreId>=0) && Settings::getGeneral_autoScroll())
1533  {
1534  QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(maxHomographyScoreId>=0?maxHomographyScoreId:maxScoreId));
1535  if(label)
1536  {
1537  ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
1538  }
1539  }
1540 
1541  // Emit homographies
1542  if(info.objDetected_.size() > 1)
1543  {
1544  UINFO("(%s) %d objects detected!",
1545  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1546  (int)info.objDetected_.size());
1547  }
1548  else if(info.objDetected_.size() == 1)
1549  {
1550  UINFO("(%s) Object %d detected!",
1551  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1552  (int)info.objDetected_.begin().key());
1553  }
1554  else if(Settings::getGeneral_sendNoObjDetectedEvents())
1555  {
1556  UINFO("(%s) No objects detected.",
1557  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
1558  }
1559 
1560  if(info.objDetected_.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
1561  {
1562  Q_EMIT objectsFound(info, header, depth, depthConstant);
1563  }
1564  ui_->label_objectsDetected->setNum(info.objDetected_.size());
1565  }
1566  else
1567  {
1568  guiRefreshTime.start();
1569 
1570  if(findObject_->vocabulary()->size())
1571  {
1572  this->statusBar()->showMessage(tr("Cannot search, objects must be updated!"));
1573  }
1574  ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
1575  ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
1576  ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
1577  ui_->label_timeSubPix->setNum(info.timeStamps_.value(DetectionInfo::kTimeSubPixelRefining, 0));
1578  ui_->imageView_source->updateImage(cvtCvMat2QImage(sceneImage_));
1579  ui_->imageView_source->updateData(info.sceneKeypoints_, info.sceneWords_);
1580  }
1581 
1582 
1583  //Update object pictures
1584  for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
1585  {
1586  iter.value()->update();
1587  }
1588 
1589  ui_->label_nfeatures->setNum((int)info.sceneKeypoints_.size());
1590  ui_->imageView_source->update();
1591 
1592  ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
1593 
1594  //update slider
1595  if(ui_->horizontalSlider_frames->isEnabled())
1596  {
1597  ui_->horizontalSlider_frames->blockSignals(true);
1598  ui_->horizontalSlider_frames->setValue(camera_->getCurrentFrameIndex()-1);
1599  ui_->label_frame->setNum(camera_->getCurrentFrameIndex()-1);
1600  ui_->horizontalSlider_frames->blockSignals(false);
1601  }
1602 
1603  ui_->label_timeTotal->setNum(info.timeStamps_.value(DetectionInfo::kTimeTotal, 0));
1604  int refreshRate = qRound(1000.0f/float(updateRate_.restart()));
1605  if(refreshRate > 0 && refreshRate < lowestRefreshRate_)
1606  {
1607  lowestRefreshRate_ = refreshRate;
1608  }
1609  // Refresh the label only after each 1000 ms
1610  if(refreshStartTime_.elapsed() > 1000)
1611  {
1612  if(Settings::getCamera_4imageRate()>0.0)
1613  {
1614  ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(Settings::getCamera_4imageRate())).arg(QString::number(lowestRefreshRate_)));
1615  }
1616  else
1617  {
1618  ui_->label_timeRefreshRate->setText(QString("(%2 Hz)").arg(QString::number(lowestRefreshRate_)));
1619  }
1620  lowestRefreshRate_ = 99;
1621  refreshStartTime_.start();
1622  }
1623 
1624  ui_->label_timeRefreshGUI->setNum(guiRefreshTime.elapsed());
1625 }
1626 
1627 void MainWindow::notifyParametersChanged(const QStringList & paramChanged)
1628 {
1629  //Selective update (to not update all objects for a simple camera's parameter modification)
1630  bool detectorDescriptorParamsChanged = false;
1631  bool nearestNeighborParamsChanged = false;
1632  bool parameterChanged = false;
1633  for(QStringList::const_iterator iter = paramChanged.begin(); iter!=paramChanged.end(); ++iter)
1634  {
1635  if(lastObjectsUpdateParameters_.value(*iter) != Settings::getParameter(*iter))
1636  {
1638  parameterChanged = true;
1639  UINFO("Parameter changed: %s -> \"%s\"", iter->toStdString().c_str(), Settings::getParameter(*iter).toString().toStdString().c_str());
1640 
1641  if(iter->contains("Feature2D"))
1642  {
1643  detectorDescriptorParamsChanged = true;
1644  }
1645  else if( (iter->contains("NearestNeighbor") && Settings::getGeneral_invertedSearch()) ||
1646  iter->compare(Settings::kGeneral_invertedSearch()) == 0 ||
1647  (iter->compare(Settings::kGeneral_vocabularyIncremental()) == 0 && Settings::getGeneral_invertedSearch()) ||
1648  (iter->compare(Settings::kGeneral_vocabularyFixed()) == 0 && Settings::getGeneral_invertedSearch()) ||
1649  (iter->compare(Settings::kGeneral_threads()) == 0 && !Settings::getGeneral_invertedSearch()) )
1650  {
1651  nearestNeighborParamsChanged = true;
1652  }
1653 
1654  if(iter->compare(Settings::kGeneral_port()) == 0 &&
1655  Settings::getGeneral_port() != ui_->label_port->text().toInt() &&
1656  Settings::getGeneral_port() != 0)
1657  {
1658  setupTCPServer();
1659  }
1660  }
1661  }
1662 
1663  if(detectorDescriptorParamsChanged)
1664  {
1665  //Re-init detector and extractor
1667  }
1668 
1669  if(Settings::getGeneral_autoUpdateObjects())
1670  {
1671  if(detectorDescriptorParamsChanged)
1672  {
1673  this->updateObjects();
1674  }
1675  else if(nearestNeighborParamsChanged)
1676  {
1677  this->updateVocabulary();
1678  }
1679  }
1680  else if(objWidgets_.size() && (detectorDescriptorParamsChanged || nearestNeighborParamsChanged))
1681  {
1682  this->statusBar()->showMessage(tr("A parameter has changed... \"Update objects\" may be required."));
1683  }
1684 
1685  if(parameterChanged &&
1686  !camera_->isRunning() &&
1687  !sceneImage_.empty() &&
1688  !(Settings::getGeneral_autoUpdateObjects() && detectorDescriptorParamsChanged)) // already done in updateObjects() above
1689  {
1690  this->update(sceneImage_);
1691  ui_->label_timeRefreshRate->setVisible(false);
1692  }
1693  ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && !UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
1694  ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
1695  ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
1696 
1697  if(Settings::getGeneral_debug())
1698  {
1699  ULogger::setPrintWhere(true);
1701  }
1702  else
1703  {
1704  ULogger::setPrintWhere(false);
1706  }
1707 }
1708 
1709 } // namespace find_object
d
void addObjectFromTcp(const cv::Mat &image, int id, const QString &filePath)
Definition: MainWindow.cpp:880
virtual void keyPressEvent(QKeyEvent *event)
Definition: MainWindow.cpp:330
void updateVocabulary(const QList< int > &ids=QList< int >())
void moveCameraFrame(int frame)
static QVariant getParameter(const QString &key)
Definition: Settings.h:343
QHostAddress getHostAddress() const
Definition: TcpServer.cpp:49
f
std::vector< double > values
virtual void takeImage()
Definition: Camera.cpp:124
virtual bool start()
Definition: Camera.cpp:186
const QPixmap & pixmap() const
Definition: ObjWidget.h:83
TcpServer * tcpServer_
Definition: MainWindow.h:146
XmlRpcServer s
virtual bool isRunning()
Definition: Camera.h:50
std::vector< cv::KeyPoint > sceneKeypoints_
Definition: DetectionInfo.h:80
bool detect(const cv::Mat &image, find_object::DetectionInfo &info) const
void updateObjectSize(find_object::ObjWidget *obj)
Definition: MainWindow.cpp:738
const cv::Mat & image() const
Definition: ObjSignature.h:68
QMultiMap< int, RejectedCode > rejectedCodes_
Definition: DetectionInfo.h:88
static void loadWindowSettings(QByteArray &windowGeometry, QByteArray &windowState, const QString &fileName=QString())
Definition: Settings.cpp:260
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
bool loadSession(const QString &path, const ParametersMap &customParameters=ParametersMap())
Definition: FindObject.cpp:82
const std::list< std::string > & getFileNames() const
Definition: UDirectory.h:125
void showObject(find_object::ObjWidget *obj)
#define UASSERT(condition)
void objectsFound(const find_object::DetectionInfo &, const find_object::Header &header, const cv::Mat &depth, float depthConstant)
static QString currentDetectorType()
Definition: Settings.cpp:1494
static const ParametersMap & getParameters()
Definition: Settings.h:338
QMap< int, QByteArray > imagesMap_
Definition: MainWindow.h:144
void updateVocabulary(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:950
void moveToFrame(int frame)
Definition: Camera.cpp:103
void setSourceImageText(const QString &text)
Definition: MainWindow.cpp:364
void setDeletable(bool deletable)
Definition: ObjWidget.cpp:417
rtabmap::PdfPlotCurve * likelihoodCurve_
Definition: MainWindow.h:136
void removeObject(find_object::ObjWidget *object)
Definition: MainWindow.cpp:683
QMap< TimeStamp, float > timeStamps_
Definition: DetectionInfo.h:79
void setKptColor(int index, const QColor &color)
Definition: ObjWidget.cpp:346
const QMap< int, ObjSignature * > & objects() const
Definition: FindObject.h:88
QMap< QString, QVariant > lastObjectsUpdateParameters_
Definition: MainWindow.h:145
AboutDialog * aboutDialog_
Definition: MainWindow.h:138
bool loadVocabulary(const QString &filePath)
Definition: FindObject.cpp:196
QMultiMap< int, QTransform > objDetected_
Definition: DetectionInfo.h:71
FindObject * findObject_
Definition: MainWindow.h:135
ROSCPP_DECL bool ok()
void updateObjects(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:856
void notifyParametersChanged(const QStringList &param)
void addRect(QGraphicsRectItem *rect)
Definition: ObjWidget.cpp:377
QMap< QString, QVariant > ParametersMap
Definition: Settings.h:41
void update(const cv::Mat &image)
int getTotalFrames()
Definition: Camera.cpp:77
const Vocabulary * vocabulary() const
Definition: FindObject.h:89
static QString currentDescriptorType()
Definition: Settings.cpp:1500
rtabmap::PdfPlotCurve * inliersCurve_
Definition: MainWindow.h:137
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:368
static ParametersMap loadSettings(const QString &fileName=QString())
Definition: Settings.cpp:107
QMultiMap< int, QMultiMap< int, int > > objDetectedInliers_
Definition: DetectionInfo.h:76
quint16 getPort() const
Definition: TcpServer.cpp:73
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:314
static QString workingDirectory()
Definition: Settings.cpp:74
int addObjectFromFile(const QString &filePath)
Definition: MainWindow.cpp:861
void removeObject(int id)
Definition: FindObject.cpp:366
virtual void closeEvent(QCloseEvent *event)
Definition: MainWindow.cpp:299
#define UDEBUG(...)
virtual void stop()
Definition: Camera.cpp:58
bool saveSession(const QString &path)
Definition: FindObject.cpp:144
#define UERROR(...)
QMultiMap< int, int > sceneWords_
Definition: DetectionInfo.h:82
ULogger class and convenient macros.
bool saveVocabulary(const QString &filePath) const
Definition: FindObject.cpp:172
#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
const QColor & color() const
Definition: ObjWidget.h:80
Ui_mainWindow * ui_
Definition: MainWindow.h:133
void setupCameraFromImagesDirectory()
Definition: MainWindow.cpp:963
const std::vector< cv::KeyPoint > keypoints() const
Definition: ObjWidget.h:81
QMultiMap< int, QMultiMap< int, int > > objDetectedOutliers_
Definition: DetectionInfo.h:77
int getCurrentFrameIndex()
Definition: Camera.cpp:90
static void saveSettings(const QString &fileName=QString())
Definition: Settings.cpp:288
const ObjSignature * addObject(const QString &filePath)
Definition: FindObject.cpp:283
FINDOBJECT_EXP QImage cvtCvMat2QImage(const cv::Mat &image, bool isBgr=true)
Definition: QtOpenCV.cpp:34
QMap< int, find_object::ObjWidget * > objWidgets_
Definition: MainWindow.h:139
void retrieveObject(ObjWidget **widget, ObjSignature **signature)
#define UINFO(...)


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09