00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "find_object/MainWindow.h"
00029 #include "find_object/Camera.h"
00030 #include "find_object/Settings.h"
00031 #include "find_object/TcpServer.h"
00032 #include "find_object/FindObject.h"
00033 #include "find_object/utilite/ULogger.h"
00034 #include "find_object/ObjWidget.h"
00035 #include "find_object/QtOpenCV.h"
00036
00037 #include "AddObjectDialog.h"
00038 #include "ui_mainWindow.h"
00039 #include "KeypointItem.h"
00040 #include "RectItem.h"
00041 #include "ParametersToolBox.h"
00042 #include "AboutDialog.h"
00043 #include "rtabmap/PdfPlot.h"
00044 #include "Vocabulary.h"
00045 #include "ObjSignature.h"
00046
00047 #include <iostream>
00048 #include <stdio.h>
00049
00050 #include "opencv2/calib3d/calib3d.hpp"
00051 #include "opencv2/imgproc/imgproc.hpp"
00052 #include "opencv2/gpu/gpu.hpp"
00053
00054 #include <QtCore/QTextStream>
00055 #include <QtCore/QFile>
00056 #include <QtCore/QBuffer>
00057 #include <QtCore/QThread>
00058 #include <QtCore/QLineF>
00059
00060 #include <QtGui/QFileDialog>
00061 #include <QtGui/QMessageBox>
00062 #include <QtGui/QGraphicsScene>
00063 #include <QtGui/QGraphicsRectItem>
00064 #include <QtGui/QSpinBox>
00065 #include <QtGui/QStatusBar>
00066 #include <QtGui/QProgressDialog>
00067 #include <QtGui/QCloseEvent>
00068 #include <QtGui/QCheckBox>
00069 #include <QtGui/QScrollBar>
00070 #include <QtGui/QInputDialog>
00071
00072 #include "utilite/UDirectory.h"
00073
00074 namespace find_object {
00075
00076
00077 MainWindow::MainWindow(FindObject * findObject, Camera * camera, QWidget * parent) :
00078 QMainWindow(parent),
00079 camera_(camera),
00080 findObject_(findObject),
00081 likelihoodCurve_(0),
00082 inliersCurve_(0),
00083 lowestRefreshRate_(99),
00084 objectsModified_(false),
00085 tcpServer_(0)
00086 {
00087 UASSERT(findObject_ != 0);
00088
00089 ui_ = new Ui_mainWindow();
00090 ui_->setupUi(this);
00091 aboutDialog_ = new AboutDialog(this);
00092 this->setStatusBar(new QStatusBar());
00093
00094 likelihoodCurve_ = new rtabmap::PdfPlotCurve("Likelihood", &imagesMap_, this);
00095 inliersCurve_ = new rtabmap::PdfPlotCurve("Inliers", &imagesMap_, this);
00096 likelihoodCurve_->setPen(QPen(Qt::blue));
00097 inliersCurve_->setPen(QPen(Qt::red));
00098 ui_->likelihoodPlot->addCurve(likelihoodCurve_, false);
00099 ui_->likelihoodPlot->addCurve(inliersCurve_, false);
00100 ui_->likelihoodPlot->setGraphicsView(true);
00101
00102 ui_->dockWidget_statistics->setVisible(false);
00103 ui_->dockWidget_parameters->setVisible(false);
00104 ui_->dockWidget_plot->setVisible(false);
00105 ui_->widget_controls->setVisible(false);
00106
00107 QByteArray geometry;
00108 QByteArray state;
00109 Settings::loadWindowSettings(geometry, state);
00110 this->restoreGeometry(geometry);
00111 this->restoreState(state);
00112 lastObjectsUpdateParameters_ = Settings::getParameters();
00113
00114 ui_->toolBox->setupUi();
00115
00116 if(!camera_)
00117 {
00118 camera_ = new Camera(this);
00119 }
00120 else
00121 {
00122 camera_->setParent(this);
00123 ui_->toolBox->getParameterWidget(Settings::kCamera_1deviceId())->setEnabled(false);
00124 ui_->toolBox->getParameterWidget(Settings::kCamera_2imageWidth())->setEnabled(false);
00125 ui_->toolBox->getParameterWidget(Settings::kCamera_3imageHeight())->setEnabled(false);
00126 ui_->toolBox->getParameterWidget(Settings::kCamera_5mediaPath())->setEnabled(false);
00127 ui_->toolBox->getParameterWidget(Settings::kCamera_6useTcpCamera())->setEnabled(false);
00128 ui_->toolBox->getParameterWidget(Settings::kCamera_8port())->setEnabled(false);
00129 ui_->toolBox->getParameterWidget(Settings::kCamera_9queueSize())->setEnabled(false);
00130 ui_->actionCamera_from_video_file->setVisible(false);
00131 ui_->actionCamera_from_TCP_IP->setVisible(false);
00132 ui_->actionCamera_from_directory_of_images->setVisible(false);
00133 ui_->actionLoad_scene_from_file->setVisible(false);
00134 }
00135
00136 if(cv::gpu::getCudaEnabledDeviceCount() == 0)
00137 {
00138 #if FINDOBJECT_NONFREE == 1
00139 ui_->toolBox->updateParameter(Settings::kFeature2D_SURF_gpu());
00140 ui_->toolBox->getParameterWidget(Settings::kFeature2D_SURF_gpu())->setEnabled(false);
00141 ui_->toolBox->getParameterWidget(Settings::kFeature2D_SURF_keypointsRatio())->setEnabled(false);
00142 #endif
00143 ui_->toolBox->updateParameter(Settings::kFeature2D_Fast_gpu());
00144 ui_->toolBox->updateParameter(Settings::kFeature2D_ORB_gpu());
00145 ui_->toolBox->updateParameter(Settings::kNearestNeighbor_BruteForce_gpu());
00146 ui_->toolBox->getParameterWidget(Settings::kFeature2D_Fast_gpu())->setEnabled(false);
00147 ui_->toolBox->getParameterWidget(Settings::kFeature2D_Fast_keypointsRatio())->setEnabled(false);
00148 ui_->toolBox->getParameterWidget(Settings::kFeature2D_ORB_gpu())->setEnabled(false);
00149 ui_->toolBox->getParameterWidget(Settings::kNearestNeighbor_BruteForce_gpu())->setEnabled(false);
00150 }
00151
00152 connect((QDoubleSpinBox*)ui_->toolBox->getParameterWidget(Settings::kCamera_4imageRate()),
00153 SIGNAL(editingFinished()),
00154 camera_,
00155 SLOT(updateImageRate()));
00156 ui_->menuView->addAction(ui_->dockWidget_statistics->toggleViewAction());
00157 ui_->menuView->addAction(ui_->dockWidget_parameters->toggleViewAction());
00158 ui_->menuView->addAction(ui_->dockWidget_objects->toggleViewAction());
00159 ui_->menuView->addAction(ui_->dockWidget_plot->toggleViewAction());
00160 connect(ui_->toolBox, SIGNAL(parametersChanged(const QStringList &)), this, SLOT(notifyParametersChanged(const QStringList &)));
00161
00162 ui_->imageView_source->setGraphicsViewMode(true);
00163 ui_->imageView_source->setTextLabel(tr("Press \"space\" to start the camera or drop an image here..."));
00164 ui_->imageView_source->setMirrorView(Settings::getGeneral_mirrorView());
00165 connect((QCheckBox*)ui_->toolBox->getParameterWidget(Settings::kGeneral_mirrorView()),
00166 SIGNAL(stateChanged(int)),
00167 this,
00168 SLOT(updateMirrorView()));
00169
00170 ui_->widget_controls->setVisible(Settings::getGeneral_controlsShown());
00171 connect((QCheckBox*)ui_->toolBox->getParameterWidget(Settings::kGeneral_controlsShown()),
00172 SIGNAL(stateChanged(int)),
00173 this,
00174 SLOT(showHideControls()));
00175
00176
00177 connect(ui_->pushButton_restoreDefaults, SIGNAL(clicked()), ui_->toolBox, SLOT(resetCurrentPage()));
00178 connect(ui_->pushButton_updateObjects, SIGNAL(clicked()), this, SLOT(updateObjects()));
00179 connect(ui_->horizontalSlider_objectsSize, SIGNAL(valueChanged(int)), this, SLOT(updateObjectsSize()));
00180
00181 ui_->actionStop_camera->setEnabled(false);
00182 ui_->actionPause_camera->setEnabled(false);
00183 ui_->actionSave_objects->setEnabled(false);
00184 ui_->actionSave_session->setEnabled(false);
00185
00186
00187 connect(ui_->actionAdd_object_from_scene, SIGNAL(triggered()), this, SLOT(addObjectFromScene()));
00188 connect(ui_->actionAdd_objects_from_files, SIGNAL(triggered()), this, SLOT(addObjectsFromFiles()));
00189 connect(ui_->actionLoad_scene_from_file, SIGNAL(triggered()), this, SLOT(loadSceneFromFile()));
00190 connect(ui_->actionStart_camera, SIGNAL(triggered()), this, SLOT(startProcessing()));
00191 connect(ui_->actionStop_camera, SIGNAL(triggered()), this, SLOT(stopProcessing()));
00192 connect(ui_->actionPause_camera, SIGNAL(triggered()), this, SLOT(pauseProcessing()));
00193 connect(ui_->actionExit, SIGNAL(triggered()), this, SLOT(close()));
00194 connect(ui_->actionSave_objects, SIGNAL(triggered()), this, SLOT(saveObjects()));
00195 connect(ui_->actionLoad_objects, SIGNAL(triggered()), this, SLOT(loadObjects()));
00196 connect(ui_->actionCamera_from_video_file, SIGNAL(triggered()), this, SLOT(setupCameraFromVideoFile()));
00197 connect(ui_->actionCamera_from_directory_of_images, SIGNAL(triggered()), this, SLOT(setupCameraFromImagesDirectory()));
00198 connect(ui_->actionCamera_from_TCP_IP, SIGNAL(triggered()), this, SLOT(setupCameraFromTcpIp()));
00199 connect(ui_->actionAbout, SIGNAL(triggered()), aboutDialog_ , SLOT(exec()));
00200 connect(ui_->actionRestore_all_default_settings, SIGNAL(triggered()), ui_->toolBox, SLOT(resetAllPages()));
00201 connect(ui_->actionRemove_all_objects, SIGNAL(triggered()), this, SLOT(removeAllObjects()));
00202 connect(ui_->actionSave_settings, SIGNAL(triggered()), this, SLOT(saveSettings()));
00203 connect(ui_->actionLoad_settings, SIGNAL(triggered()), this, SLOT(loadSettings()));
00204 connect(ui_->actionSave_session, SIGNAL(triggered()), this, SLOT(saveSession()));
00205 connect(ui_->actionLoad_session, SIGNAL(triggered()), this, SLOT(loadSession()));
00206 connect(ui_->actionShow_objects_features, SIGNAL(triggered()), this, SLOT(showObjectsFeatures()));
00207 connect(ui_->actionHide_objects_features, SIGNAL(triggered()), this, SLOT(hideObjectsFeatures()));
00208
00209 connect(ui_->pushButton_play, SIGNAL(clicked()), this, SLOT(startProcessing()));
00210 connect(ui_->pushButton_stop, SIGNAL(clicked()), this, SLOT(stopProcessing()));
00211 connect(ui_->pushButton_pause, SIGNAL(clicked()), this, SLOT(pauseProcessing()));
00212 connect(ui_->horizontalSlider_frames, SIGNAL(valueChanged(int)), this, SLOT(moveCameraFrame(int)));
00213 connect(ui_->horizontalSlider_frames, SIGNAL(valueChanged(int)), ui_->label_frame, SLOT(setNum(int)));
00214 ui_->pushButton_play->setVisible(true);
00215 ui_->pushButton_pause->setVisible(false);
00216 ui_->pushButton_stop->setEnabled(false);
00217 ui_->horizontalSlider_frames->setEnabled(false);
00218 ui_->label_frame->setVisible(false);
00219
00220 ui_->objects_area->addAction(ui_->actionAdd_object_from_scene);
00221 ui_->objects_area->addAction(ui_->actionAdd_objects_from_files);
00222 ui_->objects_area->setContextMenuPolicy(Qt::ActionsContextMenu);
00223
00224 ui_->actionStart_camera->setShortcut(Qt::Key_Space);
00225 ui_->actionPause_camera->setShortcut(Qt::Key_Space);
00226
00227 ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && !UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()));
00228 ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()));
00229 ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
00230
00231 ui_->label_ipAddress->setTextInteractionFlags(Qt::TextSelectableByMouse);
00232 ui_->label_port->setTextInteractionFlags(Qt::TextSelectableByMouse);
00233 setupTCPServer();
00234
00235 if(findObject_->objects().size())
00236 {
00237
00238 for(QMap<int, ObjSignature *>::const_iterator iter = findObject_->objects().constBegin();
00239 iter!=findObject_->objects().constEnd();
00240 ++iter)
00241 {
00242 ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), cvtCvMat2QImage(iter.value()->image()));
00243 objWidgets_.insert(obj->id(), obj);
00244 this->showObject(obj);
00245 }
00246 }
00247
00248
00249 if(Settings::getGeneral_autoStartCamera())
00250 {
00251
00252 QTimer::singleShot(1, this, SLOT(startProcessing()));
00253 }
00254
00255
00256 connect(ui_->imageDrop_objects, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(addObjectsFromFiles(const QStringList &)));
00257 connect(ui_->imageDrop_scene, SIGNAL(imagesReceived(const QStringList &)), this, SLOT(loadSceneFromFile(const QStringList &)));
00258 }
00259
00260 MainWindow::~MainWindow()
00261 {
00262 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00263 disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
00264 camera_->stop();
00265 qDeleteAll(objWidgets_);
00266 objWidgets_.clear();
00267 delete ui_;
00268 delete findObject_;
00269 }
00270
00271 void MainWindow::closeEvent(QCloseEvent * event)
00272 {
00273 bool quit = true;
00274 this->stopProcessing();
00275 if(objectsModified_ && this->isVisible() && objWidgets_.size())
00276 {
00277 int ret = QMessageBox::question(this, tr("Save new objects"), tr("Do you want to save added objects?"), QMessageBox::Yes | QMessageBox::No | QMessageBox::Cancel);
00278 switch(ret)
00279 {
00280 case QMessageBox::Yes:
00281 quit = this->saveObjects();
00282 break;
00283 case QMessageBox::Cancel:
00284 quit = false;
00285 break;
00286 case QMessageBox::No:
00287 default:
00288 break;
00289 }
00290 }
00291 if(quit)
00292 {
00293 Settings::saveWindowSettings(this->saveGeometry(), this->saveState());
00294 event->accept();
00295 }
00296 else
00297 {
00298 event->ignore();
00299 }
00300 }
00301
00302 void MainWindow::setupTCPServer()
00303 {
00304 if(tcpServer_)
00305 {
00306 tcpServer_->close();
00307 delete tcpServer_;
00308 }
00309 tcpServer_ = new TcpServer(Settings::getGeneral_port(), this);
00310 connect(this, SIGNAL(objectsFound(find_object::DetectionInfo)), tcpServer_, SLOT(publishDetectionInfo(find_object::DetectionInfo)));
00311 ui_->label_ipAddress->setText(tcpServer_->getHostAddress().toString());
00312 ui_->label_port->setNum(tcpServer_->getPort());
00313 UINFO("Detection sent on port: %d (IP=%s)", tcpServer_->getPort(), tcpServer_->getHostAddress().toString().toStdString().c_str());
00314
00315
00316 connect(tcpServer_, SIGNAL(addObject(const cv::Mat &, int, const QString &)), this, SLOT(addObjectFromTcp(const cv::Mat &, int, const QString &)));
00317 connect(tcpServer_, SIGNAL(removeObject(int)), this, SLOT(removeObject(int)));
00318 }
00319
00320 void MainWindow::setSourceImageText(const QString & text)
00321 {
00322 ui_->imageView_source->setTextLabel(text);
00323 }
00324
00325 void MainWindow::loadSession()
00326 {
00327 if(objWidgets_.size())
00328 {
00329 QMessageBox::StandardButton b = QMessageBox::question(this, tr("Loading session..."),
00330 tr("There are some objects (%1) already loaded, they will be "
00331 "deleted when loading the session. Do you want to continue?").arg(objWidgets_.size()),
00332 QMessageBox::Yes | QMessageBox::No, QMessageBox::NoButton);
00333 if(b != QMessageBox::Yes)
00334 {
00335 return;
00336 }
00337 }
00338
00339 QString path = QFileDialog::getOpenFileName(this, tr("Load session..."), Settings::workingDirectory(), "*.bin");
00340 if(!path.isEmpty())
00341 {
00342 qDeleteAll(objWidgets_);
00343 objWidgets_.clear();
00344 ui_->actionSave_objects->setEnabled(false);
00345 findObject_->removeAllObjects();
00346
00347 if(findObject_->loadSession(path))
00348 {
00349
00350 const ParametersMap & parameters = Settings::getParameters();
00351 for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
00352 {
00353 ui_->toolBox->updateParameter(iter.key());
00354 }
00355
00356
00357 for(QMap<int, ObjSignature *>::const_iterator iter=findObject_->objects().constBegin(); iter!=findObject_->objects().constEnd();++iter)
00358 {
00359 if(iter.value())
00360 {
00361 ObjWidget * obj = new ObjWidget(iter.key(), iter.value()->keypoints(), cvtCvMat2QImage(iter.value()->image()));
00362 objWidgets_.insert(obj->id(), obj);
00363 ui_->actionSave_objects->setEnabled(true);
00364 ui_->actionSave_session->setEnabled(true);
00365 this->showObject(obj);
00366
00367
00368 QLabel * title = qFindChild<QLabel*>(this, QString("%1title").arg(iter.value()->id()));
00369 title->setText(QString("%1 (%2)").arg(iter.value()->id()).arg(QString::number(iter.value()->keypoints().size())));
00370 }
00371
00372 }
00373
00374 QMessageBox::information(this, tr("Session loaded!"), tr("Session \"%1\" successfully loaded (%2 objects)!").arg(path).arg(objWidgets_.size()));
00375
00376 if(!camera_->isRunning() && !sceneImage_.empty())
00377 {
00378 this->update(sceneImage_);
00379 }
00380 }
00381 }
00382 }
00383 void MainWindow::saveSession()
00384 {
00385 if(objWidgets_.size())
00386 {
00387 QString path = QFileDialog::getSaveFileName(this, tr("Save session..."), Settings::workingDirectory(), "*.bin");
00388 if(!path.isEmpty())
00389 {
00390 if(QFileInfo(path).suffix().compare("bin") != 0)
00391 {
00392 path.append(".bin");
00393 }
00394
00395 if(findObject_->saveSession(path))
00396 {
00397 QMessageBox::information(this, tr("Session saved!"), tr("Session \"%1\" successfully saved (%2 objects)!").arg(path).arg(objWidgets_.size()));
00398 }
00399 }
00400 }
00401 }
00402
00403 void MainWindow::loadSettings()
00404 {
00405 QString path = QFileDialog::getOpenFileName(this, tr("Load settings..."), Settings::workingDirectory(), "*.ini");
00406 if(!path.isEmpty())
00407 {
00408 if(QFileInfo(path).suffix().compare("ini") != 0)
00409 {
00410 path.append(".ini");
00411 }
00412 loadSettings(path);
00413 }
00414 }
00415 void MainWindow::saveSettings()
00416 {
00417 QString path = QFileDialog::getSaveFileName(this, tr("Save settings..."), Settings::workingDirectory(), "*.ini");
00418 if(!path.isEmpty())
00419 {
00420 if(QFileInfo(path).suffix().compare("ini") != 0)
00421 {
00422 path.append(".ini");
00423 }
00424 saveSettings(path);
00425 }
00426 }
00427
00428 bool MainWindow::loadSettings(const QString & path)
00429 {
00430 if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
00431 {
00432 QByteArray geometry;
00433 QByteArray state;
00434 Settings::loadSettings(path);
00435 Settings::loadWindowSettings(geometry, state, path);
00436 this->restoreGeometry(geometry);
00437 this->restoreState(state);
00438
00439
00440 const ParametersMap & parameters = Settings::getParameters();
00441 for(ParametersMap::const_iterator iter = parameters.begin(); iter!= parameters.constEnd(); ++iter)
00442 {
00443 ui_->toolBox->updateParameter(iter.key());
00444 }
00445
00446 return true;
00447 }
00448 UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
00449 return false;
00450 }
00451
00452 bool MainWindow::saveSettings(const QString & path) const
00453 {
00454 if(!path.isEmpty() && QFileInfo(path).suffix().compare("ini") == 0)
00455 {
00456 Settings::saveSettings(path);
00457 Settings::saveWindowSettings(this->saveGeometry(), this->saveState(), path);
00458 return true;
00459 }
00460 UERROR("Path \"%s\" not valid (should be *.ini)", path.toStdString().c_str());
00461 return false;
00462 }
00463
00464 int MainWindow::loadObjects(const QString & dirPath)
00465 {
00466 QList<int> loadedObjects;
00467 QString formats = Settings::getGeneral_imageFormats().remove('*').remove('.');
00468 UDirectory dir(dirPath.toStdString(), formats.toStdString());
00469 if(dir.isValid())
00470 {
00471 const std::list<std::string> & names = dir.getFileNames();
00472 for(std::list<std::string>::const_iterator iter=names.begin(); iter!=names.end(); ++iter)
00473 {
00474 int id = this->addObjectFromFile((dirPath.toStdString()+dir.separator()+*iter).c_str());
00475 if(id >= 0)
00476 {
00477 loadedObjects.push_back(id);
00478 }
00479 }
00480 if(loadedObjects.size())
00481 {
00482 this->updateObjects(loadedObjects);
00483 }
00484 }
00485 return loadedObjects.size();
00486 }
00487
00488 int MainWindow::saveObjects(const QString & dirPath)
00489 {
00490 int count = 0;
00491 QDir dir(dirPath);
00492 if(dir.exists())
00493 {
00494 for(QMap<int, ObjWidget*>::const_iterator iter=objWidgets_.constBegin(); iter!=objWidgets_.constEnd(); ++iter)
00495 {
00496 if(iter.value()->pixmap().save(QString("%1/%2.png").arg(dirPath).arg(iter.key())))
00497 {
00498 ++count;
00499 }
00500 else
00501 {
00502 UERROR("Failed to save object %d", iter.key());
00503 }
00504 }
00505 objectsModified_ = false;
00506 }
00507 return count;
00508 }
00509
00510 void MainWindow::loadObjects()
00511 {
00512 QString dirPath = QFileDialog::getExistingDirectory(this, tr("Loading objects... Select a directory."), Settings::workingDirectory());
00513 if(!dirPath.isEmpty())
00514 {
00515 int count = loadObjects(dirPath);
00516 if(count)
00517 {
00518 QMessageBox::information(this, tr("Loading..."), tr("%1 objects loaded from \"%2\".").arg(count).arg(dirPath));
00519 }
00520 else
00521 {
00522 QMessageBox::information(this, tr("Loading..."), tr("No objects loaded from \"%1\"!").arg(dirPath));
00523 }
00524 }
00525 }
00526 bool MainWindow::saveObjects()
00527 {
00528 QString dirPath = QFileDialog::getExistingDirectory(this, tr("Saving objects... Select a directory."), Settings::workingDirectory());
00529 if(!dirPath.isEmpty())
00530 {
00531 int count = saveObjects(dirPath);
00532 if(count)
00533 {
00534 QMessageBox::information(this, tr("Saving..."), tr("%1 objects saved to \"%2\".").arg(count).arg(dirPath));
00535 }
00536 else
00537 {
00538 QMessageBox::warning(this, tr("Saving..."), tr("No objects saved to %1!").arg(dirPath));
00539 }
00540 return count > 0;
00541 }
00542 return false;
00543 }
00544
00545 void MainWindow::removeObject(find_object::ObjWidget * object)
00546 {
00547 if(object)
00548 {
00549 objWidgets_.remove(object->id());
00550 if(objWidgets_.size() == 0)
00551 {
00552 ui_->actionSave_objects->setEnabled(false);
00553 ui_->actionSave_session->setEnabled(false);
00554 }
00555 findObject_->removeObject(object->id());
00556 object->deleteLater();
00557 if(Settings::getGeneral_autoUpdateObjects())
00558 {
00559 this->updateVocabulary();
00560 }
00561 if(!camera_->isRunning() && !sceneImage_.empty())
00562 {
00563 this->update(sceneImage_);
00564 }
00565 }
00566 }
00567
00568 void MainWindow::removeObject(int id)
00569 {
00570 if(objWidgets_.contains(id))
00571 {
00572 removeObject(objWidgets_[id]);
00573 }
00574 else
00575 {
00576 UERROR("Remove object: Object %d not found!", id);
00577 }
00578 }
00579
00580 void MainWindow::removeAllObjects()
00581 {
00582 qDeleteAll(objWidgets_);
00583 objWidgets_.clear();
00584 ui_->actionSave_objects->setEnabled(false);
00585 findObject_->removeAllObjects();
00586 if(!camera_->isRunning() && !sceneImage_.empty())
00587 {
00588 this->update(sceneImage_);
00589 }
00590 }
00591
00592 void MainWindow::updateObjectsSize()
00593 {
00594 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
00595 {
00596 updateObjectSize(iter.value());
00597 }
00598 }
00599
00600 void MainWindow::updateObjectSize(ObjWidget * obj)
00601 {
00602 if(obj)
00603 {
00604 int value = ui_->horizontalSlider_objectsSize->value();
00605 if((obj->pixmap().width()*value)/100 > 4 && (obj->pixmap().height()*value)/100 > 4)
00606 {
00607 obj->setVisible(true);
00608 obj->setMinimumSize((obj->pixmap().width()*value)/100, (obj->pixmap().height())*value/100);
00609 }
00610 else
00611 {
00612 obj->setVisible(false);
00613 }
00614 }
00615 }
00616
00617 void MainWindow::updateMirrorView()
00618 {
00619 bool mirrorView = Settings::getGeneral_mirrorView();
00620 ui_->imageView_source->setMirrorView(mirrorView);
00621 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
00622 {
00623 iter.value()->setMirrorView(mirrorView);
00624 }
00625 }
00626
00627 void MainWindow::showHideControls()
00628 {
00629 ui_->widget_controls->setVisible(Settings::getGeneral_controlsShown());
00630 }
00631
00632 void MainWindow::showObjectsFeatures()
00633 {
00634 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
00635 {
00636 iter.value()->setFeaturesShown(true);
00637 }
00638 }
00639
00640 void MainWindow::hideObjectsFeatures()
00641 {
00642 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
00643 {
00644 iter.value()->setFeaturesShown(false);
00645 }
00646 }
00647
00648 void MainWindow::addObjectFromScene()
00649 {
00650 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00651 disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
00652 AddObjectDialog * dialog;
00653 bool resumeCamera = camera_->isRunning();
00654 if(camera_->isRunning() || sceneImage_.empty())
00655 {
00656 dialog = new AddObjectDialog(camera_, cv::Mat(), ui_->imageView_source->isMirrorView(), this);
00657 }
00658 else
00659 {
00660 dialog = new AddObjectDialog(0, sceneImage_, ui_->imageView_source->isMirrorView(), this);
00661 }
00662 if(dialog->exec() == QDialog::Accepted)
00663 {
00664 ObjWidget * obj = 0;
00665 ObjSignature * signature = 0;
00666 dialog->retrieveObject(&obj, &signature);
00667 UASSERT(obj!=0 && signature!=0);
00668 findObject_->addObject(signature);
00669 obj->setId(signature->id());
00670 objWidgets_.insert(obj->id(), obj);
00671 ui_->actionSave_objects->setEnabled(true);
00672 ui_->actionSave_session->setEnabled(true);
00673 showObject(obj);
00674 updateVocabulary();
00675 objectsModified_ = true;
00676 }
00677 if(resumeCamera || sceneImage_.empty())
00678 {
00679 this->startProcessing();
00680 }
00681 else
00682 {
00683 connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
00684 connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
00685 if(!sceneImage_.empty())
00686 {
00687 this->update(sceneImage_);
00688 }
00689 }
00690 delete dialog;
00691 }
00692
00693 void MainWindow::addObjectsFromFiles(const QStringList & fileNames)
00694 {
00695 if(fileNames.size())
00696 {
00697 QList<int> ids;
00698 for(int i=0; i<fileNames.size(); ++i)
00699 {
00700 int id = this->addObjectFromFile(fileNames.at(i));
00701 if(id >= 0)
00702 {
00703 ids.push_back(id);
00704 }
00705 }
00706 if(ids.size())
00707 {
00708 objectsModified_ = true;
00709 updateObjects(ids);
00710 }
00711 }
00712 }
00713
00714 void MainWindow::addObjectsFromFiles()
00715 {
00716 addObjectsFromFiles(QFileDialog::getOpenFileNames(this, tr("Add objects..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats())));
00717 }
00718
00719 int MainWindow::addObjectFromFile(const QString & filePath)
00720 {
00721 const ObjSignature * s = findObject_->addObject(filePath);
00722 if(s)
00723 {
00724 ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), cvtCvMat2QImage(s->image()));
00725 objWidgets_.insert(obj->id(), obj);
00726 ui_->actionSave_objects->setEnabled(true);
00727 ui_->actionSave_session->setEnabled(true);
00728 this->showObject(obj);
00729 return s->id();
00730 }
00731 else
00732 {
00733 QMessageBox::critical(this, tr("Error adding object"), tr("Failed to add object from \"%1\"").arg(filePath));
00734 return -1;
00735 }
00736 }
00737
00738 void MainWindow::addObjectFromTcp(const cv::Mat & image, int id, const QString & filePath)
00739 {
00740 if(objWidgets_.contains(id))
00741 {
00742 UERROR("Add Object: Object %d is already added.", id);
00743 }
00744 const ObjSignature * s = findObject_->addObject(image, id, filePath);
00745 if(s)
00746 {
00747 ObjWidget * obj = new ObjWidget(s->id(), std::vector<cv::KeyPoint>(), cvtCvMat2QImage(s->image()));
00748 objWidgets_.insert(obj->id(), obj);
00749 ui_->actionSave_objects->setEnabled(true);
00750 ui_->actionSave_session->setEnabled(true);
00751 this->showObject(obj);
00752 QList<int> ids;
00753 ids.push_back(obj->id());
00754 updateObjects(ids);
00755 }
00756 else
00757 {
00758 UERROR("Add Object: Error adding object %d.", id);
00759 }
00760 }
00761
00762 void MainWindow::loadSceneFromFile(const QStringList & fileNames)
00763 {
00764
00765 if(fileNames.size())
00766 {
00767 cv::Mat img = cv::imread(fileNames.first().toStdString().c_str());
00768 if(!img.empty())
00769 {
00770 this->update(img);
00771 ui_->label_timeRefreshRate->setVisible(false);
00772 }
00773 }
00774 }
00775
00776 void MainWindow::loadSceneFromFile()
00777 {
00778 QString fileName = QFileDialog::getOpenFileName(this, tr("Load scene..."), Settings::workingDirectory(), tr("Image Files (%1)").arg(Settings::getGeneral_imageFormats()));
00779 if(!fileName.isEmpty())
00780 {
00781 cv::Mat img = cv::imread(fileName.toStdString().c_str());
00782 if(!img.empty())
00783 {
00784 this->update(img);
00785 ui_->label_timeRefreshRate->setVisible(false);
00786 }
00787 }
00788 }
00789
00790 void MainWindow::setupCameraFromVideoFile()
00791 {
00792 if(!ui_->actionCamera_from_video_file->isChecked())
00793 {
00794 Settings::setCamera_5mediaPath("");
00795 ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
00796 }
00797 else
00798 {
00799 QString fileName = QFileDialog::getOpenFileName(this, tr("Setup camera from video file..."), Settings::workingDirectory(), tr("Video Files (%1)").arg(Settings::getGeneral_videoFormats()));
00800 if(!fileName.isEmpty())
00801 {
00802 Settings::setCamera_6useTcpCamera(false);
00803 ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
00804
00805 Settings::setCamera_5mediaPath(fileName);
00806 ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
00807 if(camera_->isRunning())
00808 {
00809 this->stopProcessing();
00810 this->startProcessing();
00811 }
00812 Settings::setGeneral_controlsShown(true);
00813 ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
00814 }
00815 }
00816 ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
00817 ui_->actionCamera_from_directory_of_images->setChecked(false);
00818 ui_->actionCamera_from_TCP_IP->setChecked(false);
00819 }
00820
00821 void MainWindow::setupCameraFromImagesDirectory()
00822 {
00823 if(!ui_->actionCamera_from_directory_of_images->isChecked())
00824 {
00825 Settings::setCamera_5mediaPath("");
00826 ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
00827 }
00828 else
00829 {
00830 QString directory = QFileDialog::getExistingDirectory(this, tr("Setup camera from directory of images..."), Settings::workingDirectory());
00831 if(!directory.isEmpty())
00832 {
00833 Settings::setCamera_6useTcpCamera(false);
00834 ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
00835
00836 Settings::setCamera_5mediaPath(directory);
00837 ui_->toolBox->updateParameter(Settings::kCamera_5mediaPath());
00838 if(camera_->isRunning())
00839 {
00840 this->stopProcessing();
00841 this->startProcessing();
00842 }
00843 Settings::setGeneral_controlsShown(true);
00844 ui_->toolBox->updateParameter(Settings::kGeneral_controlsShown());
00845 }
00846 }
00847 ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty());
00848 ui_->actionCamera_from_video_file->setChecked(false);
00849 ui_->actionCamera_from_TCP_IP->setChecked(false);
00850 }
00851
00852 void MainWindow::setupCameraFromTcpIp()
00853 {
00854 if(!ui_->actionCamera_from_TCP_IP->isChecked())
00855 {
00856 Settings::setCamera_6useTcpCamera(false);
00857 ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
00858 }
00859 else
00860 {
00861 bool ok;
00862 int port = QInputDialog::getInteger(this, tr("Server port..."), "Port: ", Settings::getCamera_8port(), 1, USHRT_MAX, 1, &ok);
00863
00864 if(ok)
00865 {
00866 int queue = QInputDialog::getInteger(this, tr("Queue size..."), "Images buffer size (0 means infinite): ", Settings::getCamera_9queueSize(), 0, 2147483647, 1, &ok);
00867 if(ok)
00868 {
00869 Settings::setCamera_6useTcpCamera(true);
00870 ui_->toolBox->updateParameter(Settings::kCamera_6useTcpCamera());
00871 Settings::setCamera_8port(port);
00872 ui_->toolBox->updateParameter(Settings::kCamera_8port());
00873 Settings::setCamera_9queueSize(queue);
00874 ui_->toolBox->updateParameter(Settings::kCamera_9queueSize());
00875 if(camera_->isRunning())
00876 {
00877 this->stopProcessing();
00878 }
00879 this->startProcessing();
00880 }
00881 }
00882 }
00883 ui_->actionCamera_from_directory_of_images->setChecked(false);
00884 ui_->actionCamera_from_video_file->setChecked(false);
00885 ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
00886 }
00887
00888 void MainWindow::showObject(ObjWidget * obj)
00889 {
00890 if(obj)
00891 {
00892 obj->setGraphicsViewMode(false);
00893 obj->setMirrorView(ui_->imageView_source->isMirrorView());
00894 QList<ObjWidget*> objs = ui_->objects_area->findChildren<ObjWidget*>();
00895 QVBoxLayout * vLayout = new QVBoxLayout();
00896 ui_->toolBox->updateParameter(Settings::kGeneral_nextObjID());
00897
00898 QLabel * title = new QLabel(QString("%1 (%2)").arg(obj->id()).arg(obj->keypoints().size()), this);
00899 QLabel * detectedLabel = new QLabel(this);
00900 title->setObjectName(QString("%1title").arg(obj->id()));
00901 detectedLabel->setObjectName(QString("%1detection").arg(obj->id()));
00902 QHBoxLayout * hLayout = new QHBoxLayout();
00903 hLayout->addWidget(title);
00904 hLayout->addStretch(1);
00905 hLayout->addStretch(1);
00906 hLayout->addWidget(detectedLabel);
00907 vLayout->addLayout(hLayout);
00908 vLayout->addWidget(obj);
00909 obj->setDeletable(true);
00910 connect(obj, SIGNAL(removalTriggered(find_object::ObjWidget*)), this, SLOT(removeObject(find_object::ObjWidget*)));
00911 connect(obj, SIGNAL(destroyed(QObject *)), title, SLOT(deleteLater()));
00912 connect(obj, SIGNAL(destroyed(QObject *)), detectedLabel, SLOT(deleteLater()));
00913 connect(obj, SIGNAL(destroyed(QObject *)), vLayout, SLOT(deleteLater()));
00914 ui_->verticalLayout_objects->insertLayout(ui_->verticalLayout_objects->count()-1, vLayout);
00915
00916 QByteArray ba;
00917 QBuffer buffer(&ba);
00918 buffer.open(QIODevice::WriteOnly);
00919 obj->pixmap().scaledToWidth(128).save(&buffer, "JPEG");
00920 imagesMap_.insert(obj->id(), ba);
00921
00922
00923 int objectsPanelWidth = ui_->dockWidget_objects->width();
00924 if(objectsPanelWidth > 0 && (obj->pixmap().width()*ui_->horizontalSlider_objectsSize->value()) / 100 > objectsPanelWidth)
00925 {
00926 ui_->horizontalSlider_objectsSize->setValue((objectsPanelWidth * 100) / obj->pixmap().width());
00927 }
00928 else
00929 {
00930 updateObjectSize(obj);
00931 }
00932 }
00933 }
00934
00935 void MainWindow::updateObjects(const QList<int> & ids)
00936 {
00937 if(ids.size())
00938 {
00939 this->statusBar()->showMessage(tr("Updating %1 objects...").arg(ids.size()));
00940 QApplication::processEvents();
00941
00942 findObject_->updateObjects(ids);
00943
00944 updateVocabulary();
00945
00946 QList<ObjSignature*> signatures = findObject_->objects().values();
00947 for(int i=0; i<signatures.size(); ++i)
00948 {
00949 if(ids.contains(signatures[i]->id()))
00950 {
00951 objWidgets_.value(signatures[i]->id())->setData(signatures[i]->keypoints(), cvtCvMat2QImage(signatures[i]->image()));
00952
00953
00954 QLabel * title = qFindChild<QLabel*>(this, QString("%1title").arg(signatures[i]->id()));
00955 title->setText(QString("%1 (%2)").arg(signatures[i]->id()).arg(QString::number(signatures[i]->keypoints().size())));
00956 }
00957 }
00958
00959 if(!camera_->isRunning() && !sceneImage_.empty())
00960 {
00961 this->update(sceneImage_);
00962 }
00963 this->statusBar()->clearMessage();
00964 }
00965 }
00966
00967 void MainWindow::updateObjects()
00968 {
00969 updateObjects(objWidgets_.keys());
00970 }
00971
00972 void MainWindow::updateVocabulary()
00973 {
00974 this->statusBar()->showMessage(tr("Updating vocabulary..."));
00975 QApplication::processEvents();
00976
00977 QTime time;
00978 time.start();
00979 findObject_->updateVocabulary();
00980
00981 if(findObject_->vocabulary()->size())
00982 {
00983 ui_->label_timeIndexing->setNum(time.elapsed());
00984 ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
00985 }
00986 lastObjectsUpdateParameters_ = Settings::getParameters();
00987 this->statusBar()->clearMessage();
00988 }
00989
00990 void MainWindow::startProcessing()
00991 {
00992 UINFO("Starting camera...");
00993 bool updateStatusMessage = this->statusBar()->currentMessage().isEmpty();
00994 if(updateStatusMessage)
00995 {
00996 this->statusBar()->showMessage(tr("Starting camera..."));
00997 }
00998 if(camera_->start())
00999 {
01000 connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)), Qt::UniqueConnection);
01001 connect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()), Qt::UniqueConnection);
01002 ui_->actionStop_camera->setEnabled(true);
01003 ui_->actionPause_camera->setEnabled(true);
01004 ui_->actionStart_camera->setEnabled(false);
01005 ui_->actionLoad_scene_from_file->setEnabled(false);
01006 ui_->actionCamera_from_directory_of_images->setEnabled(false);
01007 ui_->actionCamera_from_video_file->setEnabled(false);
01008 ui_->actionCamera_from_TCP_IP->setEnabled(false);
01009 ui_->label_timeRefreshRate->setVisible(true);
01010
01011
01012 ui_->pushButton_play->setVisible(false);
01013 ui_->pushButton_pause->setVisible(true);
01014 ui_->pushButton_stop->setEnabled(true);
01015 int totalFrames = camera_->getTotalFrames();
01016 if(totalFrames>0)
01017 {
01018 ui_->label_frame->setVisible(true);
01019 ui_->horizontalSlider_frames->setEnabled(true);
01020 ui_->horizontalSlider_frames->setMaximum(totalFrames-1);
01021 }
01022
01023
01024 ui_->label_port_image->setText("-");
01025 if(Settings::getCamera_6useTcpCamera() && camera_->getPort())
01026 {
01027 ui_->label_port_image->setNum(camera_->getPort());
01028 }
01029
01030 if(updateStatusMessage)
01031 {
01032 this->statusBar()->showMessage(tr("Camera started."), 2000);
01033 }
01034 }
01035 else
01036 {
01037 if(updateStatusMessage)
01038 {
01039 this->statusBar()->clearMessage();
01040 }
01041
01042 if(Settings::getCamera_6useTcpCamera())
01043 {
01044 QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with port %1)").arg(Settings::getCamera_8port()));
01045 }
01046 else
01047 {
01048 QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_1deviceId()));
01049 }
01050 }
01051 }
01052
01053 void MainWindow::stopProcessing()
01054 {
01055 if(camera_)
01056 {
01057 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
01058 disconnect(camera_, SIGNAL(finished()), this, SLOT(stopProcessing()));
01059 camera_->stop();
01060 }
01061 ui_->actionStop_camera->setEnabled(false);
01062 ui_->actionPause_camera->setEnabled(false);
01063 ui_->actionStart_camera->setEnabled(true);
01064 ui_->actionLoad_scene_from_file->setEnabled(true);
01065 ui_->actionCamera_from_directory_of_images->setEnabled(true);
01066 ui_->actionCamera_from_video_file->setEnabled(true);
01067 ui_->actionCamera_from_TCP_IP->setEnabled(true);
01068 ui_->pushButton_play->setVisible(true);
01069 ui_->pushButton_pause->setVisible(false);
01070 ui_->pushButton_stop->setEnabled(false);
01071 ui_->horizontalSlider_frames->setEnabled(false);
01072 ui_->horizontalSlider_frames->setValue(0);
01073 ui_->label_frame->setVisible(false);
01074 ui_->label_port_image->setText("-");
01075 }
01076
01077 void MainWindow::pauseProcessing()
01078 {
01079 ui_->actionStop_camera->setEnabled(true);
01080 ui_->actionPause_camera->setEnabled(true);
01081 ui_->actionStart_camera->setEnabled(false);
01082 if(camera_->isRunning())
01083 {
01084 ui_->pushButton_play->setVisible(true);
01085 ui_->pushButton_pause->setVisible(false);
01086 camera_->pause();
01087 }
01088 else
01089 {
01090 ui_->pushButton_play->setVisible(false);
01091 ui_->pushButton_pause->setVisible(true);
01092 camera_->start();
01093 }
01094 }
01095
01096 void MainWindow::moveCameraFrame(int frame)
01097 {
01098 if(ui_->horizontalSlider_frames->isEnabled())
01099 {
01100 camera_->moveToFrame(frame);
01101 if(!camera_->isRunning())
01102 {
01103 camera_->takeImage();
01104 }
01105 }
01106 }
01107
01108 void MainWindow::rectHovered(int objId)
01109 {
01110 if(objId>=0 && Settings::getGeneral_autoScroll())
01111 {
01112 QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(objId));
01113 if(label)
01114 {
01115 ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
01116 }
01117 }
01118 }
01119
01120 void MainWindow::update(const cv::Mat & image)
01121 {
01122 if(image.empty())
01123 {
01124 UWARN("The image received is empty...");
01125 return;
01126 }
01127 sceneImage_ = image.clone();
01128
01129
01130 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
01131 {
01132 iter.value()->resetKptsColor();
01133 }
01134
01135 QTime guiRefreshTime;
01136
01137 DetectionInfo info;
01138 if(findObject_->detect(sceneImage_, info))
01139 {
01140 guiRefreshTime.start();
01141 ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
01142 ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
01143 ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
01144 ui_->imageView_source->setData(info.sceneKeypoints_, cvtCvMat2QImage(sceneImage_));
01145 if(!findObject_->vocabulary()->size())
01146 {
01147 ui_->label_timeIndexing->setNum(info.timeStamps_.value(DetectionInfo::kTimeIndexing, 0));
01148 }
01149 ui_->label_timeMatching->setNum(info.timeStamps_.value(DetectionInfo::kTimeMatching, 0));
01150 ui_->label_timeHomographies->setNum(info.timeStamps_.value(DetectionInfo::kTimeHomography, 0));
01151
01152 ui_->label_vocabularySize->setNum(findObject_->vocabulary()->size());
01153
01154
01155 const QMap<int, QMultiMap<int, int> > & matches = info.matches_;
01156 QMap<int, int> scores;
01157 int maxScoreId = -1;
01158 int maxScore = 0;
01159 for(QMap<int, QMultiMap<int, int> >::const_iterator jter=matches.constBegin(); jter!=matches.end();++jter)
01160 {
01161 scores.insert(jter.key(), jter.value().size());
01162 if(maxScoreId == -1 || maxScore < jter.value().size())
01163 {
01164 maxScoreId = jter.key();
01165 maxScore = jter.value().size();
01166 }
01167
01168 int id = jter.key();
01169 QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
01170 if(!Settings::getHomography_homographyComputed())
01171 {
01172 label->setText(QString("%1 matches").arg(jter.value().size()));
01173
01174 ObjWidget * obj = objWidgets_.value(id);
01175 UASSERT(obj != 0);
01176
01177 for(QMultiMap<int, int>::const_iterator iter = jter.value().constBegin(); iter!= jter.value().constEnd(); ++iter)
01178 {
01179 obj->setKptColor(iter.key(), obj->color());
01180 ui_->imageView_source->setKptColor(iter.value(), obj->color());
01181 }
01182 }
01183 else if(!info.objDetected_.contains(id))
01184 {
01185
01186 QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
01187 QMultiMap<int, int> rejectedInliers = info.rejectedInliers_.value(id);
01188 QMultiMap<int, int> rejectedOutliers = info.rejectedOutliers_.value(id);
01189 int rejectedCode = info.rejectedCodes_.value(id);
01190 if(rejectedCode == DetectionInfo::kRejectedLowMatches)
01191 {
01192 label->setText(QString("Too low matches (%1)").arg(jter.value().size()));
01193 }
01194 else if(rejectedCode == DetectionInfo::kRejectedAllInliers)
01195 {
01196 label->setText(QString("Ignored, all inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
01197 }
01198 else if(rejectedCode == DetectionInfo::kRejectedNotValid)
01199 {
01200 label->setText(QString("Not valid homography (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
01201 }
01202 else if(rejectedCode == DetectionInfo::kRejectedLowInliers)
01203 {
01204 label->setText(QString("Too low inliers (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
01205 }
01206 else if(rejectedCode == DetectionInfo::kRejectedCornersOutside)
01207 {
01208 label->setText(QString("Corners not visible (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
01209 }
01210 else if(rejectedCode == DetectionInfo::kRejectedByAngle)
01211 {
01212 label->setText(QString("Angle too small (%1 in %2 out)").arg(rejectedInliers.size()).arg(rejectedOutliers.size()));
01213 }
01214 }
01215 }
01216
01217 if(camera_->isRunning() && Settings::getGeneral_autoPauseOnDetection() && info.objDetected_.size())
01218 {
01219 this->pauseProcessing();
01220 }
01221
01222
01223 QMultiMap<int, QMultiMap<int,int> >::const_iterator inliersIter = info.objDetectedInliers_.constBegin();
01224 QMultiMap<int, QMultiMap<int,int> >::const_iterator outliersIter = info.objDetectedOutliers_.constBegin();
01225 for(QMultiMap<int,QTransform>::iterator iter = info.objDetected_.begin();
01226 iter!=info.objDetected_.end();
01227 ++iter, ++inliersIter, ++outliersIter)
01228 {
01229 int id = iter.key();
01230 ObjWidget * obj = objWidgets_.value(id);
01231 UASSERT(obj != 0);
01232
01233
01234 QTransform hTransform = iter.value();
01235
01236 QRect rect = obj->pixmap().rect();
01237
01238 QPen rectPen(obj->color());
01239 rectPen.setWidth(Settings::getHomography_rectBorderWidth());
01240 RectItem * rectItemScene = new RectItem(id, rect);
01241 connect(rectItemScene, SIGNAL(hovered(int)), this, SLOT(rectHovered(int)));
01242 rectItemScene->setPen(rectPen);
01243 rectItemScene->setTransform(hTransform);
01244 ui_->imageView_source->addRect(rectItemScene);
01245
01246 QGraphicsRectItem * rectItemObj = new QGraphicsRectItem(rect);
01247 rectItemObj->setPen(rectPen);
01248 obj->addRect(rectItemObj);
01249
01250 for(QMultiMap<int, int>::const_iterator iter = inliersIter.value().constBegin(); iter!= inliersIter.value().constEnd(); ++iter)
01251 {
01252 obj->setKptColor(iter.key(), obj->color());
01253 ui_->imageView_source->setKptColor(iter.value(), obj->color());
01254 }
01255
01256 QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(id));
01257 if(info.objDetected_.count(id) > 1)
01258 {
01259
01260 label->setText(QString("%1 objects found").arg(info.objDetected_.count(id)));
01261 }
01262 else
01263 {
01264 label->setText(QString("%1 in %2 out").arg(inliersIter.value().size()).arg(outliersIter.value().size()));
01265 }
01266 }
01267
01268
01269
01270 likelihoodCurve_->setData(scores, QMap<int, int>());
01271 QMap<int, int> inlierScores;
01272 for(QMap<int, int>::iterator iter=scores.begin(); iter!=scores.end(); ++iter)
01273 {
01274 QList<QMultiMap<int, int> > values = info.objDetectedInliers_.values(iter.key());
01275 int maxValue = 0;
01276 if(values.size())
01277 {
01278 maxValue = values[0].size();
01279 for(int i=1; i<values.size(); ++i)
01280 {
01281 if(maxValue < values[i].size())
01282 {
01283 maxValue = values[i].size();
01284 }
01285 }
01286 }
01287 inlierScores.insert(iter.key(), maxValue);
01288 }
01289 inliersCurve_->setData(inlierScores, QMap<int, int>());
01290 if(ui_->likelihoodPlot->isVisible())
01291 {
01292 ui_->likelihoodPlot->update();
01293 }
01294
01295 ui_->label_minMatchedDistance->setNum(info.minMatchedDistance_);
01296 ui_->label_maxMatchedDistance->setNum(info.maxMatchedDistance_);
01297
01298
01299 if(maxScoreId>=0 && Settings::getGeneral_autoScroll())
01300 {
01301 QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(maxScoreId));
01302 if(label)
01303 {
01304 ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
01305 }
01306 }
01307
01308
01309 if(info.objDetected_.size() > 1)
01310 {
01311 UINFO("(%s) %d objects detected!",
01312 QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
01313 (int)info.objDetected_.size());
01314 }
01315 else if(info.objDetected_.size() == 1)
01316 {
01317 UINFO("(%s) Object %d detected!",
01318 QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
01319 (int)info.objDetected_.begin().key());
01320 }
01321 else if(Settings::getGeneral_sendNoObjDetectedEvents())
01322 {
01323 UINFO("(%s) No objects detected.",
01324 QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
01325 }
01326
01327 if(info.objDetected_.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
01328 {
01329 Q_EMIT objectsFound(info);
01330 }
01331 ui_->label_objectsDetected->setNum(info.objDetected_.size());
01332 }
01333 else
01334 {
01335 guiRefreshTime.start();
01336
01337 if(findObject_->vocabulary()->size())
01338 {
01339 this->statusBar()->showMessage(tr("Cannot search, objects must be updated!"));
01340 }
01341 ui_->label_timeDetection->setNum(info.timeStamps_.value(DetectionInfo::kTimeKeypointDetection, 0));
01342 ui_->label_timeSkewAffine->setNum(info.timeStamps_.value(DetectionInfo::kTimeSkewAffine, 0));
01343 ui_->label_timeExtraction->setNum(info.timeStamps_.value(DetectionInfo::kTimeDescriptorExtraction, 0));
01344 ui_->imageView_source->setData(info.sceneKeypoints_, cvtCvMat2QImage(sceneImage_));
01345 }
01346
01347
01348
01349 for(QMap<int, ObjWidget*>::iterator iter=objWidgets_.begin(); iter!=objWidgets_.end(); ++iter)
01350 {
01351 iter.value()->update();
01352 }
01353
01354 ui_->label_nfeatures->setNum((int)info.sceneKeypoints_.size());
01355 ui_->imageView_source->update();
01356
01357 ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
01358
01359
01360 if(ui_->horizontalSlider_frames->isEnabled())
01361 {
01362 ui_->horizontalSlider_frames->blockSignals(true);
01363 ui_->horizontalSlider_frames->setValue(camera_->getCurrentFrameIndex()-1);
01364 ui_->label_frame->setNum(camera_->getCurrentFrameIndex()-1);
01365 ui_->horizontalSlider_frames->blockSignals(false);
01366 }
01367
01368 ui_->label_timeTotal->setNum(info.timeStamps_.value(DetectionInfo::kTimeTotal, 0));
01369 int refreshRate = qRound(1000.0f/float(updateRate_.restart()));
01370 if(refreshRate > 0 && refreshRate < lowestRefreshRate_)
01371 {
01372 lowestRefreshRate_ = refreshRate;
01373 }
01374
01375 if(refreshStartTime_.elapsed() > 1000)
01376 {
01377 if(Settings::getCamera_4imageRate()>0.0)
01378 {
01379 ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(Settings::getCamera_4imageRate())).arg(QString::number(lowestRefreshRate_)));
01380 }
01381 else
01382 {
01383 ui_->label_timeRefreshRate->setText(QString("(%2 Hz)").arg(QString::number(lowestRefreshRate_)));
01384 }
01385 lowestRefreshRate_ = 99;
01386 refreshStartTime_.start();
01387 }
01388
01389 ui_->label_timeRefreshGUI->setNum(guiRefreshTime.elapsed());
01390 }
01391
01392 void MainWindow::notifyParametersChanged(const QStringList & paramChanged)
01393 {
01394
01395 bool detectorDescriptorParamsChanged = false;
01396 bool nearestNeighborParamsChanged = false;
01397 bool parameterChanged = false;
01398 for(QStringList::const_iterator iter = paramChanged.begin(); iter!=paramChanged.end(); ++iter)
01399 {
01400 if(lastObjectsUpdateParameters_.value(*iter) != Settings::getParameter(*iter))
01401 {
01402 lastObjectsUpdateParameters_[*iter] = Settings::getParameter(*iter);
01403 parameterChanged = true;
01404 UINFO("Parameter changed: %s -> \"%s\"", iter->toStdString().c_str(), Settings::getParameter(*iter).toString().toStdString().c_str());
01405
01406 if(iter->contains("Feature2D"))
01407 {
01408 detectorDescriptorParamsChanged = true;
01409 }
01410 else if( (iter->contains("NearestNeighbor") && Settings::getGeneral_invertedSearch()) ||
01411 iter->compare(Settings::kGeneral_invertedSearch()) == 0 ||
01412 (iter->compare(Settings::kGeneral_vocabularyIncremental()) == 0 && Settings::getGeneral_invertedSearch()) ||
01413 (iter->compare(Settings::kGeneral_threads()) == 0 && !Settings::getGeneral_invertedSearch()) )
01414 {
01415 nearestNeighborParamsChanged = true;
01416 }
01417
01418 if(iter->compare(Settings::kGeneral_port()) == 0 &&
01419 Settings::getGeneral_port() != ui_->label_port->text().toInt() &&
01420 Settings::getGeneral_port() != 0)
01421 {
01422 setupTCPServer();
01423 }
01424 }
01425 }
01426
01427 if(detectorDescriptorParamsChanged)
01428 {
01429
01430 findObject_->updateDetectorExtractor();
01431 }
01432
01433 if(Settings::getGeneral_autoUpdateObjects())
01434 {
01435 if(detectorDescriptorParamsChanged)
01436 {
01437 this->updateObjects(objWidgets_.keys());
01438 }
01439 else if(nearestNeighborParamsChanged)
01440 {
01441 this->updateVocabulary();
01442 }
01443 }
01444 else if(objWidgets_.size() && (detectorDescriptorParamsChanged || nearestNeighborParamsChanged))
01445 {
01446 this->statusBar()->showMessage(tr("A parameter has changed... \"Update objects\" may be required."));
01447 }
01448 if(parameterChanged && !camera_->isRunning() && !sceneImage_.empty())
01449 {
01450 this->update(sceneImage_);
01451 ui_->label_timeRefreshRate->setVisible(false);
01452 }
01453
01454 ui_->actionCamera_from_video_file->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && !UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
01455 ui_->actionCamera_from_directory_of_images->setChecked(!Settings::getCamera_5mediaPath().isEmpty() && UDirectory::exists(Settings::getCamera_5mediaPath().toStdString()) && !Settings::getCamera_6useTcpCamera());
01456 ui_->actionCamera_from_TCP_IP->setChecked(Settings::getCamera_6useTcpCamera());
01457 }
01458
01459 }