AddObjectDialog.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/Camera.h"
29 #include "find_object/Settings.h"
31 #include "find_object/ObjWidget.h"
32 #include "find_object/QtOpenCV.h"
33 
34 #include "AddObjectDialog.h"
35 #include "ui_addObjectDialog.h"
36 #include "KeypointItem.h"
37 #include "ObjSignature.h"
38 
39 #include <stdio.h>
40 
41 #include <QGraphicsScene>
42 #include <QGraphicsPixmapItem>
43 #include <QMessageBox>
44 
45 #include <opencv2/imgproc/imgproc.hpp>
46 #include <opencv2/highgui/highgui.hpp>
47 #include <opencv2/imgproc/imgproc_c.h>
48 
49 namespace find_object {
50 
51 AddObjectDialog::AddObjectDialog(Camera * camera, const cv::Mat & image, bool mirrorView, QWidget * parent, Qt::WindowFlags f) :
52  QDialog(parent, f),
53  camera_(camera),
54  objWidget_(0),
55  objSignature_(0)
56 {
57  ui_ = new Ui_addObjectDialog();
58  ui_->setupUi(this);
59 
62  UASSERT(detector_ != 0 && extractor_ != 0);
63 
64  connect(ui_->pushButton_cancel, SIGNAL(clicked()), this, SLOT(cancel()));
65  connect(ui_->pushButton_back, SIGNAL(clicked()), this, SLOT(back()));
66  connect(ui_->pushButton_next, SIGNAL(clicked()), this, SLOT(next()));
67  connect(ui_->pushButton_takePicture, SIGNAL(clicked()), this, SLOT(takePicture()));
68  connect(ui_->comboBox_selection, SIGNAL(currentIndexChanged(int)), this, SLOT(changeSelectionMode()));
69 
70  connect(ui_->cameraView, SIGNAL(selectionChanged()), this, SLOT(updateNextButton()));
71  connect(ui_->cameraView, SIGNAL(roiChanged(const cv::Rect &)), this, SLOT(updateNextButton(const cv::Rect &)));
72  ui_->cameraView->setMirrorView(mirrorView);
73 
74  if((camera_ && camera_->isRunning()) || image.empty())
75  {
76  this->setState(kTakePicture);
77  }
78  else if(!image.empty())
79  {
80  update(image);
82  }
83 }
84 
86 {
87  delete detector_;
88  delete extractor_;
89  if(objWidget_)
90  {
91  delete objWidget_;
92  objWidget_ = 0;
93  }
94  if(objSignature_)
95  {
96  delete objSignature_;
97  objSignature_ = 0;
98  }
99  delete ui_;
100 }
101 
103 {
104  *widget = objWidget_;
105  objWidget_= 0;
106  *signature = objSignature_;
107  objSignature_ = 0;
108 }
109 
110 void AddObjectDialog::closeEvent(QCloseEvent* event)
111 {
112  if(camera_)
113  {
114  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
115  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)));
116  }
117  QDialog::closeEvent(event);
118 }
119 
121 {
122  setState(state_+1);
123 }
125 {
126  setState(state_-1);
127 }
129 {
130  this->reject();
131 }
133 {
134  next();
135 }
136 
138 {
139  updateNextButton(cv::Rect());
140 }
141 
142 void AddObjectDialog::updateNextButton(const cv::Rect & rect)
143 {
144  roi_ = rect;
145  if(roi_.height && roi_.width && cameraImage_.cols)
146  {
147  //clip roi
148  if( roi_.x >= cameraImage_.cols ||
149  roi_.x+roi_.width <= 0 ||
150  roi_.y >= cameraImage_.rows ||
151  roi_.y+roi_.height <= 0)
152  {
153  //Not valid...
154  roi_ = cv::Rect();
155  }
156  else
157  {
158  if(roi_.x < 0)
159  {
160  roi_.x = 0;
161  }
162  if(roi_.x + roi_.width > cameraImage_.cols)
163  {
164  roi_.width = cameraImage_.cols - roi_.x;
165  }
166  if(roi_.y < 0)
167  {
168  roi_.y = 0;
169  }
170  if(roi_.y + roi_.height > cameraImage_.rows)
171  {
172  roi_.height = cameraImage_.rows - roi_.y;
173  }
174  }
175  }
176  if(state_ == kSelectFeatures)
177  {
178  if(ui_->comboBox_selection->currentIndex() == 1)
179  {
180  if(ui_->cameraView->selectedItems().size() > 0)
181  {
182  ui_->pushButton_next->setEnabled(true);
183  }
184  else
185  {
186  ui_->pushButton_next->setEnabled(false);
187  }
188  }
189  else
190  {
191  if(roi_.width == 0 || roi_.height == 0)
192  {
193  ui_->pushButton_next->setEnabled(false);
194  }
195  else
196  {
197  ui_->pushButton_next->setEnabled(true);
198  }
199  }
200  }
201 }
202 
204 {
205  this->setState(kSelectFeatures);
206 }
207 
209 {
210  state_ = state;
211  if(state == kTakePicture)
212  {
213  ui_->pushButton_cancel->setEnabled(true);
214  ui_->pushButton_back->setEnabled(false);
215  ui_->pushButton_next->setEnabled(false);
216  ui_->pushButton_takePicture->setEnabled(true);
217  ui_->label_instruction->setText(tr("Place the object in front of the camera and click \"Take picture\"."));
218  ui_->pushButton_next->setText(tr("Next"));
219  ui_->cameraView->setVisible(true);
220  ui_->cameraView->clearRoiSelection();
221  ui_->objectView->setVisible(false);
222  ui_->cameraView->setGraphicsViewMode(false);
223  ui_->comboBox_selection->setVisible(false);
224  if(!camera_ || !camera_->start())
225  {
226  QMessageBox::critical(this, tr("Camera error"), tr("Camera is not started!"));
227  ui_->pushButton_takePicture->setEnabled(false);
228  }
229  else
230  {
231  connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
232  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)));
233  }
234  }
235  else if(state == kSelectFeatures)
236  {
237  if(camera_)
238  {
239  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
240  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)));
241  camera_->pause();
242  }
243 
244  ui_->pushButton_cancel->setEnabled(true);
245  ui_->pushButton_back->setEnabled(camera_);
246  ui_->pushButton_next->setEnabled(false);
247  ui_->pushButton_takePicture->setEnabled(false);
248  ui_->pushButton_next->setText(tr("Next"));
249  ui_->cameraView->setVisible(true);
250  ui_->cameraView->clearRoiSelection();
251  ui_->objectView->setVisible(false);
252  ui_->comboBox_selection->setVisible(true);
253 
254  if(ui_->comboBox_selection->currentIndex() == 1)
255  {
256  ui_->label_instruction->setText(tr("Select features representing the object."));
257  ui_->cameraView->setGraphicsViewMode(true);
258  }
259  else
260  {
261  ui_->label_instruction->setText(tr("Select region representing the object."));
262  ui_->cameraView->setGraphicsViewMode(false);
263  }
264  updateNextButton(cv::Rect());
265  }
266  else if(state == kVerifySelection)
267  {
268  if(camera_)
269  {
270  disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
271  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)));
272  camera_->pause();
273  }
274 
275  ui_->pushButton_cancel->setEnabled(true);
276  ui_->pushButton_back->setEnabled(true);
277  ui_->pushButton_takePicture->setEnabled(false);
278  ui_->pushButton_next->setText(tr("End"));
279  ui_->cameraView->setVisible(true);
280  ui_->objectView->setVisible(true);
281  ui_->objectView->setMirrorView(ui_->cameraView->isMirrorView());
282  ui_->objectView->setSizedFeatures(ui_->cameraView->isSizedFeatures());
283  ui_->comboBox_selection->setVisible(false);
284  if(ui_->comboBox_selection->currentIndex() == 1)
285  {
286  ui_->cameraView->setGraphicsViewMode(true);
287  }
288  else
289  {
290  ui_->cameraView->setGraphicsViewMode(false);
291  }
292 
293  std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints();
294 
295  // Select keypoints
296  if(!cameraImage_.empty() &&
297  ((ui_->comboBox_selection->currentIndex() == 1 && selectedKeypoints.size()) ||
298  (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height)))
299  {
300  if(ui_->comboBox_selection->currentIndex() == 1)
301  {
302  roi_ = computeROI(selectedKeypoints);
303  }
304 
305  cv::Mat imgRoi = cv::Mat(cameraImage_, roi_).clone();
306 
307  if(ui_->comboBox_selection->currentIndex() == 1)
308  {
309  if(roi_.x != 0 || roi_.y != 0)
310  {
311  for(unsigned int i=0; i<selectedKeypoints.size(); ++i)
312  {
313  selectedKeypoints.at(i).pt.x -= roi_.x;
314  selectedKeypoints.at(i).pt.y -= roi_.y;
315  }
316  }
317  }
318  else
319  {
320  // Extract keypoints
321  selectedKeypoints.clear();
322  detector_->detect(imgRoi, selectedKeypoints);
323  }
324  ui_->objectView->updateImage(cvtCvMat2QImage(imgRoi));
325  ui_->objectView->updateData(selectedKeypoints, QMultiMap<int,int>());
326  ui_->objectView->setMinimumSize(roi_.width, roi_.height);
327  ui_->objectView->update();
328  ui_->pushButton_next->setEnabled(true);
329  }
330  else
331  {
332  UINFO("Please select items");
333  ui_->pushButton_next->setEnabled(false);
334  }
335  ui_->label_instruction->setText(tr("Selection : %1 features").arg(selectedKeypoints.size()));
336  }
337  else if(state == kClosing)
338  {
339  std::vector<cv::KeyPoint> keypoints = ui_->objectView->keypoints();
340  if((ui_->comboBox_selection->currentIndex() == 1 && keypoints.size()) ||
341  (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height))
342  {
343  cv::Mat descriptors;
344  cv::Mat imgRoi(cameraImage_, roi_);
345  if(keypoints.size())
346  {
347  // Extract descriptors
349  {
350  detector_->compute(imgRoi, keypoints, descriptors);
351  }
352  else
353  {
354  extractor_->compute(imgRoi, keypoints, descriptors);
355  }
356 
357  if(keypoints.size() != (unsigned int)descriptors.rows)
358  {
359  UERROR("keypoints=%d != descriptors=%d", (int)keypoints.size(), descriptors.rows);
360  }
361  }
362 
363  if(objWidget_)
364  {
365  delete objWidget_;
366  objWidget_ = 0;
367  }
368  if(objSignature_)
369  {
370  delete objSignature_;
371  objSignature_ = 0;
372  }
373  objSignature_ = new ObjSignature(0, imgRoi.clone(), "");
374  objSignature_->setData(keypoints, descriptors);
375  objWidget_ = new ObjWidget(0, keypoints, QMultiMap<int,int>(), cvtCvMat2QImage(imgRoi.clone()));
376 
377  this->accept();
378  }
379  }
380 }
381 
382 void AddObjectDialog::update(const cv::Mat & image)
383 {
384  update(image, Header(), cv::Mat(), 0.0);
385 }
386 
387 void AddObjectDialog::update(const cv::Mat & image, const Header & header, const cv::Mat & depth, float depthConstant)
388 {
389  cameraImage_ = cv::Mat();
390  if(!image.empty())
391  {
392  // convert to grayscale
393  if(image.channels() != 1 || image.depth() != CV_8U)
394  {
395  cv::cvtColor(image, cameraImage_, CV_BGR2GRAY);
396  }
397  else
398  {
399  cameraImage_ = image.clone();
400  }
401 
402  // Extract keypoints
403  std::vector<cv::KeyPoint> keypoints;
404  detector_->detect(cameraImage_, keypoints);
405 
406  ui_->cameraView->updateImage(cvtCvMat2QImage(cameraImage_));
407  ui_->cameraView->updateData(keypoints, QMultiMap<int,int>());
408  ui_->cameraView->update();
409  }
410  else
411  {
412  UWARN("Camera cannot get more images (maybe the end of stream is reached)...");
413  camera_->stop();
414  }
415 }
416 
417 cv::Rect AddObjectDialog::computeROI(const std::vector<cv::KeyPoint> & kpts)
418 {
419  cv::Rect roi(0,0,0,0);
420  int x1=0,x2=0,h1=0,h2=0;
421  for(unsigned int i=0; i<kpts.size(); ++i)
422  {
423  float radius = kpts.at(i).size / 2;
424  if(i==0)
425  {
426  x1 = int(kpts.at(i).pt.x - radius);
427  x2 = int(kpts.at(i).pt.x + radius);
428  h1 = int(kpts.at(i).pt.y - radius);
429  h2 = int(kpts.at(i).pt.y + radius);
430  }
431  else
432  {
433  if(x1 > int(kpts.at(i).pt.x - radius))
434  {
435  x1 = int(kpts.at(i).pt.x - radius);
436  }
437  else if(x2 < int(kpts.at(i).pt.x + radius))
438  {
439  x2 = int(kpts.at(i).pt.x + radius);
440  }
441  if(h1 > int(kpts.at(i).pt.y - radius))
442  {
443  h1 = int(kpts.at(i).pt.y - radius);
444  }
445  else if(h2 < int(kpts.at(i).pt.y + radius))
446  {
447  h2 = int(kpts.at(i).pt.y + radius);
448  }
449  }
450  roi.x = x1;
451  roi.y = h1;
452  roi.width = x2-x1;
453  roi.height = h2-h1;
454  //UINFO("ptx=%d, pty=%d", (int)kpts.at(i).pt.x, (int)kpts.at(i).pt.y);
455  //UINFO("x=%d, y=%d, w=%d, h=%d", roi.x, roi.y, roi.width, roi.height);
456  }
457 
458  return roi;
459 }
460 
461 } // namespace find_object
Ui_addObjectDialog * ui_
void update(const cv::Mat &)
static Feature2D * createKeypointDetector()
Definition: Settings.cpp:722
virtual bool start()
Definition: Camera.cpp:186
virtual bool isRunning()
Definition: Camera.h:50
#define UASSERT(condition)
static QString currentDetectorType()
Definition: Settings.cpp:1494
virtual void closeEvent(QCloseEvent *event)
AddObjectDialog(Camera *camera, const cv::Mat &image, bool mirrorView, QWidget *parent=0, Qt::WindowFlags f=0)
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:1721
void setData(const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &descriptors)
Definition: ObjSignature.h:55
static QString currentDescriptorType()
Definition: Settings.cpp:1500
cv::Rect computeROI(const std::vector< cv::KeyPoint > &kpts)
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
Definition: Settings.cpp:1742
virtual void stop()
Definition: Camera.cpp:58
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
static Feature2D * createDescriptorExtractor()
Definition: Settings.cpp:1138
FINDOBJECT_EXP QImage cvtCvMat2QImage(const cv::Mat &image, bool isBgr=true)
Definition: QtOpenCV.cpp:34
void retrieveObject(ObjWidget **widget, ObjSignature **signature)
#define UINFO(...)


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