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/Camera.h"
00029 #include "find_object/Settings.h"
00030 #include "find_object/utilite/ULogger.h"
00031 #include "find_object/ObjWidget.h"
00032 #include "find_object/QtOpenCV.h"
00033
00034 #include "AddObjectDialog.h"
00035 #include "ui_addObjectDialog.h"
00036 #include "KeypointItem.h"
00037 #include "ObjSignature.h"
00038
00039 #include <stdio.h>
00040
00041 #include <QtGui/QGraphicsScene>
00042 #include <QtGui/QGraphicsPixmapItem>
00043 #include <QtGui/QMessageBox>
00044
00045 #include <opencv2/imgproc/imgproc.hpp>
00046 #include <opencv2/highgui/highgui.hpp>
00047
00048 namespace find_object {
00049
00050 AddObjectDialog::AddObjectDialog(Camera * camera, const cv::Mat & image, bool mirrorView, QWidget * parent, Qt::WindowFlags f) :
00051 QDialog(parent, f),
00052 camera_(camera),
00053 objWidget_(0),
00054 objSignature_(0)
00055 {
00056 ui_ = new Ui_addObjectDialog();
00057 ui_->setupUi(this);
00058
00059 detector_ = Settings::createKeypointDetector();
00060 extractor_ = Settings::createDescriptorExtractor();
00061 UASSERT(detector_ != 0 && extractor_ != 0);
00062
00063 connect(ui_->pushButton_cancel, SIGNAL(clicked()), this, SLOT(cancel()));
00064 connect(ui_->pushButton_back, SIGNAL(clicked()), this, SLOT(back()));
00065 connect(ui_->pushButton_next, SIGNAL(clicked()), this, SLOT(next()));
00066 connect(ui_->pushButton_takePicture, SIGNAL(clicked()), this, SLOT(takePicture()));
00067 connect(ui_->comboBox_selection, SIGNAL(currentIndexChanged(int)), this, SLOT(changeSelectionMode()));
00068
00069 connect(ui_->cameraView, SIGNAL(selectionChanged()), this, SLOT(updateNextButton()));
00070 connect(ui_->cameraView, SIGNAL(roiChanged(const cv::Rect &)), this, SLOT(updateNextButton(const cv::Rect &)));
00071 ui_->cameraView->setMirrorView(mirrorView);
00072
00073 if((camera_ && camera_->isRunning()) || image.empty())
00074 {
00075 this->setState(kTakePicture);
00076 }
00077 else if(!image.empty())
00078 {
00079 update(image);
00080 this->setState(kSelectFeatures);
00081 }
00082 }
00083
00084 AddObjectDialog::~AddObjectDialog()
00085 {
00086 delete detector_;
00087 delete extractor_;
00088 if(objWidget_)
00089 {
00090 delete objWidget_;
00091 objWidget_ = 0;
00092 }
00093 if(objSignature_)
00094 {
00095 delete objSignature_;
00096 objSignature_ = 0;
00097 }
00098 delete ui_;
00099 }
00100
00101 void AddObjectDialog::retrieveObject(ObjWidget ** widget, ObjSignature ** signature)
00102 {
00103 *widget = objWidget_;
00104 objWidget_= 0;
00105 *signature = objSignature_;
00106 objSignature_ = 0;
00107 }
00108
00109 void AddObjectDialog::closeEvent(QCloseEvent* event)
00110 {
00111 if(camera_)
00112 {
00113 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00114 }
00115 QDialog::closeEvent(event);
00116 }
00117
00118 void AddObjectDialog::next()
00119 {
00120 setState(state_+1);
00121 }
00122 void AddObjectDialog::back()
00123 {
00124 setState(state_-1);
00125 }
00126 void AddObjectDialog::cancel()
00127 {
00128 this->reject();
00129 }
00130 void AddObjectDialog::takePicture()
00131 {
00132 next();
00133 }
00134
00135 void AddObjectDialog::updateNextButton()
00136 {
00137 updateNextButton(cv::Rect());
00138 }
00139
00140 void AddObjectDialog::updateNextButton(const cv::Rect & rect)
00141 {
00142 roi_ = rect;
00143 if(roi_.height && roi_.width && cameraImage_.cols)
00144 {
00145
00146 if( roi_.x >= cameraImage_.cols ||
00147 roi_.x+roi_.width <= 0 ||
00148 roi_.y >= cameraImage_.rows ||
00149 roi_.y+roi_.height <= 0)
00150 {
00151
00152 roi_ = cv::Rect();
00153 }
00154 else
00155 {
00156 if(roi_.x < 0)
00157 {
00158 roi_.x = 0;
00159 }
00160 if(roi_.x + roi_.width > cameraImage_.cols)
00161 {
00162 roi_.width = cameraImage_.cols - roi_.x;
00163 }
00164 if(roi_.y < 0)
00165 {
00166 roi_.y = 0;
00167 }
00168 if(roi_.y + roi_.height > cameraImage_.rows)
00169 {
00170 roi_.height = cameraImage_.rows - roi_.y;
00171 }
00172 }
00173 }
00174 if(state_ == kSelectFeatures)
00175 {
00176 if(ui_->comboBox_selection->currentIndex() == 1)
00177 {
00178 if(ui_->cameraView->selectedItems().size() > 0)
00179 {
00180 ui_->pushButton_next->setEnabled(true);
00181 }
00182 else
00183 {
00184 ui_->pushButton_next->setEnabled(false);
00185 }
00186 }
00187 else
00188 {
00189 if(roi_.width == 0 || roi_.height == 0)
00190 {
00191 ui_->pushButton_next->setEnabled(false);
00192 }
00193 else
00194 {
00195 ui_->pushButton_next->setEnabled(true);
00196 }
00197 }
00198 }
00199 }
00200
00201 void AddObjectDialog::changeSelectionMode()
00202 {
00203 this->setState(kSelectFeatures);
00204 }
00205
00206 void AddObjectDialog::setState(int state)
00207 {
00208 state_ = state;
00209 if(state == kTakePicture)
00210 {
00211 ui_->pushButton_cancel->setEnabled(true);
00212 ui_->pushButton_back->setEnabled(false);
00213 ui_->pushButton_next->setEnabled(false);
00214 ui_->pushButton_takePicture->setEnabled(true);
00215 ui_->label_instruction->setText(tr("Place the object in front of the camera and click \"Take picture\"."));
00216 ui_->pushButton_next->setText(tr("Next"));
00217 ui_->cameraView->setVisible(true);
00218 ui_->cameraView->clearRoiSelection();
00219 ui_->objectView->setVisible(false);
00220 ui_->cameraView->setGraphicsViewMode(false);
00221 ui_->comboBox_selection->setVisible(false);
00222 if(!camera_ || !camera_->start())
00223 {
00224 QMessageBox::critical(this, tr("Camera error"), tr("Camera is not started!"));
00225 ui_->pushButton_takePicture->setEnabled(false);
00226 }
00227 else
00228 {
00229 connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00230 }
00231 }
00232 else if(state == kSelectFeatures)
00233 {
00234 if(camera_)
00235 {
00236 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00237 camera_->pause();
00238 }
00239
00240 ui_->pushButton_cancel->setEnabled(true);
00241 ui_->pushButton_back->setEnabled(camera_);
00242 ui_->pushButton_next->setEnabled(false);
00243 ui_->pushButton_takePicture->setEnabled(false);
00244 ui_->pushButton_next->setText(tr("Next"));
00245 ui_->cameraView->setVisible(true);
00246 ui_->cameraView->clearRoiSelection();
00247 ui_->objectView->setVisible(false);
00248 ui_->comboBox_selection->setVisible(true);
00249
00250 if(ui_->comboBox_selection->currentIndex() == 1)
00251 {
00252 ui_->label_instruction->setText(tr("Select features representing the object."));
00253 ui_->cameraView->setGraphicsViewMode(true);
00254 }
00255 else
00256 {
00257 ui_->label_instruction->setText(tr("Select region representing the object."));
00258 ui_->cameraView->setGraphicsViewMode(false);
00259 }
00260 updateNextButton(cv::Rect());
00261 }
00262 else if(state == kVerifySelection)
00263 {
00264 if(camera_)
00265 {
00266 disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
00267 camera_->pause();
00268 }
00269
00270 ui_->pushButton_cancel->setEnabled(true);
00271 ui_->pushButton_back->setEnabled(true);
00272 ui_->pushButton_takePicture->setEnabled(false);
00273 ui_->pushButton_next->setText(tr("End"));
00274 ui_->cameraView->setVisible(true);
00275 ui_->objectView->setVisible(true);
00276 ui_->objectView->setMirrorView(ui_->cameraView->isMirrorView());
00277 ui_->objectView->setSizedFeatures(ui_->cameraView->isSizedFeatures());
00278 ui_->comboBox_selection->setVisible(false);
00279 if(ui_->comboBox_selection->currentIndex() == 1)
00280 {
00281 ui_->cameraView->setGraphicsViewMode(true);
00282 }
00283 else
00284 {
00285 ui_->cameraView->setGraphicsViewMode(false);
00286 }
00287
00288 std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints();
00289
00290
00291 if(!cameraImage_.empty() &&
00292 ((ui_->comboBox_selection->currentIndex() == 1 && selectedKeypoints.size()) ||
00293 (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height)))
00294 {
00295 if(ui_->comboBox_selection->currentIndex() == 1)
00296 {
00297 roi_ = computeROI(selectedKeypoints);
00298 }
00299
00300 cv::Mat imgRoi(cameraImage_, roi_);
00301
00302 if(ui_->comboBox_selection->currentIndex() == 1)
00303 {
00304 if(roi_.x != 0 || roi_.y != 0)
00305 {
00306 for(unsigned int i=0; i<selectedKeypoints.size(); ++i)
00307 {
00308 selectedKeypoints.at(i).pt.x -= roi_.x;
00309 selectedKeypoints.at(i).pt.y -= roi_.y;
00310 }
00311 }
00312 }
00313 else
00314 {
00315
00316 selectedKeypoints.clear();
00317 detector_->detect(imgRoi, selectedKeypoints);
00318 }
00319 ui_->objectView->setData(selectedKeypoints, cvtCvMat2QImage(imgRoi.clone()));
00320 ui_->objectView->setMinimumSize(roi_.width, roi_.height);
00321 ui_->objectView->update();
00322 ui_->pushButton_next->setEnabled(true);
00323 }
00324 else
00325 {
00326 UINFO("Please select items");
00327 ui_->pushButton_next->setEnabled(false);
00328 }
00329 ui_->label_instruction->setText(tr("Selection : %1 features").arg(selectedKeypoints.size()));
00330 }
00331 else if(state == kClosing)
00332 {
00333 std::vector<cv::KeyPoint> keypoints = ui_->objectView->keypoints();
00334 if((ui_->comboBox_selection->currentIndex() == 1 && keypoints.size()) ||
00335 (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height))
00336 {
00337 cv::Mat descriptors;
00338 cv::Mat imgRoi(cameraImage_, roi_);
00339 if(keypoints.size())
00340 {
00341
00342 extractor_->compute(imgRoi, keypoints, descriptors);
00343
00344 if(keypoints.size() != (unsigned int)descriptors.rows)
00345 {
00346 UERROR("keypoints=%d != descriptors=%d", (int)keypoints.size(), descriptors.rows);
00347 }
00348 }
00349
00350 if(objWidget_)
00351 {
00352 delete objWidget_;
00353 objWidget_ = 0;
00354 }
00355 if(objSignature_)
00356 {
00357 delete objSignature_;
00358 objSignature_ = 0;
00359 }
00360 objSignature_ = new ObjSignature(0, imgRoi.clone(), "");
00361 objSignature_->setData(keypoints, descriptors);
00362 objWidget_ = new ObjWidget(0, keypoints, cvtCvMat2QImage(imgRoi.clone()));
00363
00364 this->accept();
00365 }
00366 }
00367 }
00368
00369 void AddObjectDialog::update(const cv::Mat & image)
00370 {
00371 cameraImage_ = cv::Mat();
00372 if(!image.empty())
00373 {
00374
00375 if(image.channels() != 1 || image.depth() != CV_8U)
00376 {
00377 cv::cvtColor(image, cameraImage_, CV_BGR2GRAY);
00378 }
00379 else
00380 {
00381 cameraImage_ = image.clone();
00382 }
00383
00384
00385 cv::vector<cv::KeyPoint> keypoints;
00386 detector_->detect(cameraImage_, keypoints);
00387
00388 ui_->cameraView->setData(keypoints, cvtCvMat2QImage(cameraImage_));
00389 ui_->cameraView->update();
00390 }
00391 else
00392 {
00393 UWARN("Camera cannot get more images (maybe the end of stream is reached)...");
00394 camera_->stop();
00395 }
00396 }
00397
00398 cv::Rect AddObjectDialog::computeROI(const std::vector<cv::KeyPoint> & kpts)
00399 {
00400 cv::Rect roi(0,0,0,0);
00401 int x1=0,x2=0,h1=0,h2=0;
00402 for(unsigned int i=0; i<kpts.size(); ++i)
00403 {
00404 float radius = kpts.at(i).size / 2;
00405 if(i==0)
00406 {
00407 x1 = int(kpts.at(i).pt.x - radius);
00408 x2 = int(kpts.at(i).pt.x + radius);
00409 h1 = int(kpts.at(i).pt.y - radius);
00410 h2 = int(kpts.at(i).pt.y + radius);
00411 }
00412 else
00413 {
00414 if(x1 > int(kpts.at(i).pt.x - radius))
00415 {
00416 x1 = int(kpts.at(i).pt.x - radius);
00417 }
00418 else if(x2 < int(kpts.at(i).pt.x + radius))
00419 {
00420 x2 = int(kpts.at(i).pt.x + radius);
00421 }
00422 if(h1 > int(kpts.at(i).pt.y - radius))
00423 {
00424 h1 = int(kpts.at(i).pt.y - radius);
00425 }
00426 else if(h2 < int(kpts.at(i).pt.y + radius))
00427 {
00428 h2 = int(kpts.at(i).pt.y + radius);
00429 }
00430 }
00431 roi.x = x1;
00432 roi.y = h1;
00433 roi.width = x2-x1;
00434 roi.height = h2-h1;
00435
00436
00437 }
00438
00439 return roi;
00440 }
00441
00442 }