Visual Servoing Platform  version 3.6.1 under development (2024-04-24)
testKeyPoint-2.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Test keypoint matching and pose estimation.
32  */
33 
34 #include <iostream>
35 
36 #include <visp3/core/vpConfig.h>
37 
38 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO)
39 
40 #include <visp3/core/vpImage.h>
41 #include <visp3/core/vpIoTools.h>
42 #include <visp3/gui/vpDisplayGDI.h>
43 #include <visp3/gui/vpDisplayGTK.h>
44 #include <visp3/gui/vpDisplayOpenCV.h>
45 #include <visp3/gui/vpDisplayX.h>
46 #include <visp3/io/vpImageIo.h>
47 #include <visp3/io/vpParseArgv.h>
48 #include <visp3/io/vpVideoReader.h>
49 #include <visp3/mbt/vpMbEdgeTracker.h>
50 #include <visp3/vision/vpKeyPoint.h>
51 
52 // List of allowed command line options
53 #define GETOPTARGS "cdph"
54 
55 void usage(const char *name, const char *badparam);
56 bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display);
57 
66 void usage(const char *name, const char *badparam)
67 {
68  fprintf(stdout, "\n\
69 Test keypoints matching.\n\
70 \n\
71 SYNOPSIS\n\
72  %s [-c] [-d] [-p] [-h]\n",
73  name);
74 
75  fprintf(stdout, "\n\
76 OPTIONS: \n\
77 \n\
78  -c\n\
79  Disable the mouse click. Useful to automate the \n\
80  execution of this program without human intervention.\n\
81 \n\
82  -d \n\
83  Turn off the display.\n\
84 \n\
85  -p \n\
86  Use parallel RANSAC.\n\
87 \n\
88  -h\n\
89  Print the help.\n");
90 
91  if (badparam)
92  fprintf(stdout, "\nERROR: Bad parameter [%s]\n", badparam);
93 }
94 
106 bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display, bool &use_parallel_ransac)
107 {
108  const char *optarg_;
109  int c;
110  while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
111 
112  switch (c) {
113  case 'c':
114  click_allowed = false;
115  break;
116  case 'd':
117  display = false;
118  break;
119  case 'p':
120  use_parallel_ransac = true;
121  break;
122  case 'h':
123  usage(argv[0], nullptr);
124  return false;
125  break;
126 
127  default:
128  usage(argv[0], optarg_);
129  return false;
130  break;
131  }
132  }
133 
134  if ((c == 1) || (c == -1)) {
135  // standalone param or error
136  usage(argv[0], nullptr);
137  std::cerr << "ERROR: " << std::endl;
138  std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
139  return false;
140  }
141 
142  return true;
143 }
144 
145 template <typename Type>
146 void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_display, bool use_parallel_ransac,
147  vpImage<Type> &I, vpImage<Type> &IMatching)
148 {
149 #if VISP_HAVE_DATASET_VERSION >= 0x030600
150  std::string ext("png");
151 #else
152  std::string ext("pgm");
153 #endif
154  // Set the path location of the image sequence
155  std::string dirname = vpIoTools::createFilePath(env_ipath, "mbt/cube");
156 
157  // Build the name of the image files
158  std::string filenameRef = vpIoTools::createFilePath(dirname, "image0000." + ext);
159  vpImageIo::read(I, filenameRef);
160  std::string filenameCur = vpIoTools::createFilePath(dirname, "image%04d." + ext);
161 
162 #if defined(VISP_HAVE_X11)
164 #elif defined(VISP_HAVE_GTK)
166 #elif defined(VISP_HAVE_GDI)
168 #elif defined(HAVE_OPENCV_HIGHGUI)
170 #endif
171 
172  if (opt_display) {
173  display.setDownScalingFactor(vpDisplay::SCALE_AUTO);
174  display.init(I, 0, 0, "ORB keypoints matching and pose estimation");
175  }
176 
177  vpCameraParameters cam;
178  vpMbEdgeTracker tracker;
179  // Load config for tracker
180  std::string tracker_config_file = vpIoTools::createFilePath(env_ipath, "mbt/cube.xml");
181 
182 #if defined(VISP_HAVE_PUGYXML)
183  tracker.loadConfigFile(tracker_config_file);
184  tracker.getCameraParameters(cam);
185 #else
186  // Corresponding parameters manually set to have an example code
187  vpMe me;
188  me.setMaskSize(5);
189  me.setMaskNumber(180);
190  me.setRange(8);
192  me.setThreshold(20);
193  me.setMu1(0.5);
194  me.setMu2(0.5);
195  me.setSampleStep(4);
196  me.setNbTotalSample(250);
197  tracker.setMovingEdge(me);
198  cam.initPersProjWithoutDistortion(547.7367575, 542.0744058, 338.7036994, 234.5083345);
199  tracker.setCameraParameters(cam);
200  tracker.setNearClippingDistance(0.01);
201  tracker.setFarClippingDistance(100.0);
203 #endif
204 
205  tracker.setAngleAppear(vpMath::rad(89));
206  tracker.setAngleDisappear(vpMath::rad(89));
207 
208  // Load CAO model
209  std::string cao_model_file = vpIoTools::createFilePath(env_ipath, "mbt/cube.cao");
210  tracker.loadModel(cao_model_file);
211 
212  // Initialize the pose
213  std::string init_file = vpIoTools::createFilePath(env_ipath, "mbt/cube.init");
214  if (opt_display && opt_click_allowed) {
215  tracker.initClick(I, init_file);
216  }
217  else {
218  vpHomogeneousMatrix cMoi(0.02044769891, 0.1101505452, 0.5078963719, 2.063603907, 1.110231561, -0.4392789872);
219  tracker.initFromPose(I, cMoi);
220  }
221 
222  // Get the init pose
224  tracker.getPose(cMo);
225 
226  // Init keypoints
227  vpKeyPoint keypoints("ORB", "ORB", "BruteForce-Hamming");
228  keypoints.setRansacParallel(use_parallel_ransac);
229 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400)
230  // Bug when using LSH index with FLANN and OpenCV 2.3.1.
231  // see http://code.opencv.org/issues/1741 (Bug #1741)
232  keypoints.setMatcher("FlannBased");
233 #if (VISP_HAVE_OPENCV_VERSION < 0x030000)
234  keypoints.setDetectorParameter("ORB", "nLevels", 1);
235 #else
236  cv::Ptr<cv::ORB> orb_detector = keypoints.getDetector("ORB").dynamicCast<cv::ORB>();
237  if (orb_detector) {
238  orb_detector->setNLevels(1);
239  }
240 #endif
241 #endif
242 
243  // Detect keypoints on the current image
244  std::vector<cv::KeyPoint> trainKeyPoints;
245  double elapsedTime;
246  keypoints.detect(I, trainKeyPoints, elapsedTime);
247 
248  // Keep only keypoints on the cube
249  std::vector<vpPolygon> polygons;
250  std::vector<std::vector<vpPoint> > roisPt;
251  std::pair<std::vector<vpPolygon>, std::vector<std::vector<vpPoint> > > pair =
252  tracker.getPolygonFaces(true); // To detect an issue with CI
253  polygons = pair.first;
254  roisPt = pair.second;
255 
256  // Compute the 3D coordinates
257  std::vector<cv::Point3f> points3f;
258  vpKeyPoint::compute3DForPointsInPolygons(cMo, cam, trainKeyPoints, polygons, roisPt, points3f);
259 
260  // Build the reference keypoints
261  keypoints.buildReference(I, trainKeyPoints, points3f, false, 1);
262 
263  // Read image 150
264  filenameRef = vpIoTools::createFilePath(dirname, "image0150." + ext);
265  vpImageIo::read(I, filenameRef);
266 
267  // Init pose at image 150
268  cMo.buildFrom(0.02651282185, -0.03713587374, 0.6873765919, 2.314744454, 0.3492296488, -0.1226054828);
269  tracker.initFromPose(I, cMo);
270 
271  // Detect keypoints on the image 150
272  keypoints.detect(I, trainKeyPoints, elapsedTime);
273 
274  // Keep only keypoints on the cube
275  pair = tracker.getPolygonFaces(true, true,
276  true); // To detect an issue with CI
277  polygons = pair.first;
278  roisPt = pair.second;
279 
280  // Compute the 3D coordinates
281  vpKeyPoint::compute3DForPointsInPolygons(cMo, cam, trainKeyPoints, polygons, roisPt, points3f);
282 
283  // Build the reference keypoints
284  keypoints.buildReference(I, trainKeyPoints, points3f, true, 2);
285 
286  // Read image 200
287  filenameRef = vpIoTools::createFilePath(dirname, "image0200." + ext);
288  vpImageIo::read(I, filenameRef);
289 
290  // Init pose at image 200
291  cMo.buildFrom(0.02965448956, -0.07283091786, 0.7253526051, 2.300529617, -0.4286674806, 0.1788761025);
292  tracker.initFromPose(I, cMo);
293 
294  // Detect keypoints on the image 200
295  keypoints.detect(I, trainKeyPoints, elapsedTime);
296 
297  // Keep only keypoints on the cube
298  pair = tracker.getPolygonFaces(false); // To detect an issue with CI
299  polygons = pair.first;
300  roisPt = pair.second;
301 
302  // Compute the 3D coordinates
303  vpKeyPoint::compute3DForPointsInPolygons(cMo, cam, trainKeyPoints, polygons, roisPt, points3f);
304 
305  // Build the reference keypoints
306  keypoints.buildReference(I, trainKeyPoints, points3f, true, 3);
307 
308  // Init reader for getting the input image sequence
309  vpVideoReader g;
310  g.setFileName(filenameCur);
311  g.open(I);
312  g.acquire(I);
313 
314 #if defined(VISP_HAVE_X11)
315  vpDisplayX display2;
316 #elif defined(VISP_HAVE_GTK)
317  vpDisplayGTK display2;
318 #elif defined(VISP_HAVE_GDI)
319  vpDisplayGDI display2;
320 #elif defined(HAVE_OPENCV_HIGHGUI)
321  vpDisplayOpenCV display2;
322 #endif
323 
324  keypoints.createImageMatching(I, IMatching);
325 
326  if (opt_display) {
328  display2.init(IMatching, 0, (int)I.getHeight() / vpDisplay::getDownScalingFactor(I) + 80, "IMatching");
329  }
330 
331  bool opt_click = false;
332  double error;
334  std::vector<double> times_vec;
335  while ((opt_display && !g.end()) || (!opt_display && g.getFrameIndex() < 30)) {
336  g.acquire(I);
337 
338  if (opt_display) {
340 
341  // Display image matching
342  keypoints.insertImageMatching(I, IMatching);
343 
344  vpDisplay::display(IMatching);
345  }
346 
347  // Match keypoints and estimate the pose
348  if (keypoints.matchPoint(I, cam, cMo, error, elapsedTime)) {
349  times_vec.push_back(elapsedTime);
350 
351  tracker.setCameraParameters(cam);
352  tracker.setPose(I, cMo);
353 
354  if (opt_display) {
355  tracker.display(I, cMo, cam, vpColor::red, 2);
356  vpDisplay::displayFrame(I, cMo, cam, 0.025, vpColor::none, 3);
357 
358  std::vector<vpImagePoint> ransacInliers = keypoints.getRansacInliers();
359  std::vector<vpImagePoint> ransacOutliers = keypoints.getRansacOutliers();
360 
361  for (std::vector<vpImagePoint>::const_iterator it = ransacInliers.begin(); it != ransacInliers.end(); ++it) {
363  vpImagePoint imPt(*it);
364  imPt.set_u(imPt.get_u() + I.getWidth());
365  imPt.set_v(imPt.get_v() + I.getHeight());
366  vpDisplay::displayCircle(IMatching, imPt, 4, vpColor::green);
367  }
368 
369  for (std::vector<vpImagePoint>::const_iterator it = ransacOutliers.begin(); it != ransacOutliers.end(); ++it) {
371  vpImagePoint imPt(*it);
372  imPt.set_u(imPt.get_u() + I.getWidth());
373  imPt.set_v(imPt.get_v() + I.getHeight());
374  vpDisplay::displayCircle(IMatching, imPt, 4, vpColor::red);
375  }
376 
377  keypoints.displayMatching(I, IMatching);
378 
379  // Display model in the correct sub-image in IMatching
380  vpCameraParameters cam2;
381  cam2.initPersProjWithoutDistortion(cam.get_px(), cam.get_py(), cam.get_u0() + I.getWidth(),
382  cam.get_v0() + I.getHeight());
383  tracker.setCameraParameters(cam2);
384  tracker.setPose(IMatching, cMo);
385  tracker.display(IMatching, cMo, cam2, vpColor::red, 2);
386  vpDisplay::displayFrame(IMatching, cMo, cam2, 0.025, vpColor::none, 3);
387  }
388  }
389 
390  if (opt_display) {
391  vpDisplay::flush(I);
392  vpDisplay::flush(IMatching);
393  }
394 
395  if (opt_click_allowed && opt_display) {
396  // Click requested to process next image
397  if (opt_click) {
398  vpDisplay::getClick(I, button, true);
399  if (button == vpMouseButton::button3) {
400  opt_click = false;
401  }
402  }
403  else {
404  // Use right click to enable/disable step by step tracking
405  if (vpDisplay::getClick(I, button, false)) {
406  if (button == vpMouseButton::button3) {
407  opt_click = true;
408  }
409  else if (button == vpMouseButton::button1) {
410  break;
411  }
412  }
413  }
414  }
415  }
416 
417  if (!times_vec.empty()) {
418  std::cout << "Computation time, Mean: " << vpMath::getMean(times_vec)
419  << " ms ; Median: " << vpMath::getMedian(times_vec) << " ms ; Std: " << vpMath::getStdev(times_vec)
420  << std::endl;
421  }
422 }
423 
429 int main(int argc, const char **argv)
430 {
431  try {
432  std::string env_ipath;
433  bool opt_click_allowed = true;
434  bool opt_display = true;
435  bool use_parallel_ransac = false;
436 
437  // Read the command line options
438  if (getOptions(argc, argv, opt_click_allowed, opt_display, use_parallel_ransac) == false) {
439  return EXIT_FAILURE;
440  }
441 
442  // Get the visp-images-data package path or VISP_INPUT_IMAGE_PATH
443  // environment variable value
444  env_ipath = vpIoTools::getViSPImagesDataPath();
445 
446  if (env_ipath.empty()) {
447  std::cerr << "Please set the VISP_INPUT_IMAGE_PATH environment "
448  "variable value."
449  << std::endl;
450  return EXIT_FAILURE;
451  }
452 
453  {
454  vpImage<unsigned char> I, IMatching;
455 
456  std::cout << "-- Test on gray level images" << std::endl;
457 
458  run_test(env_ipath, opt_click_allowed, opt_display, use_parallel_ransac, I, IMatching);
459  }
460  {
461  vpImage<vpRGBa> I, IMatching;
462 
463  std::cout << "-- Test on color images" << std::endl;
464 
465  run_test(env_ipath, opt_click_allowed, opt_display, use_parallel_ransac, I, IMatching);
466  }
467 
468  }
469  catch (const vpException &e) {
470  std::cerr << e.what() << std::endl;
471  return EXIT_FAILURE;
472  }
473 
474  std::cout << "testKeyPoint-2 is ok !" << std::endl;
475  return EXIT_SUCCESS;
476 }
477 #else
478 int main()
479 {
480  std::cerr << "You need OpenCV library." << std::endl;
481 
482  return EXIT_SUCCESS;
483 }
484 
485 #endif
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
static const vpColor red
Definition: vpColor.h:211
static const vpColor none
Definition: vpColor.h:223
static const vpColor green
Definition: vpColor.h:214
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:128
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
void init(vpImage< unsigned char > &I, int win_x=-1, int win_y=-1, const std::string &win_title="") vp_override
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void displayCircle(const vpImage< unsigned char > &I, const vpImageCircle &circle, const vpColor &color, bool fill=false, unsigned int thickness=1)
virtual void setDownScalingFactor(unsigned int scale)
Definition: vpDisplay.cpp:227
static void display(const vpImage< unsigned char > &I)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void flush(const vpImage< unsigned char > &I)
@ SCALE_AUTO
Definition: vpDisplay.h:179
unsigned int getDownScalingFactor()
Definition: vpDisplay.h:231
error that can be emitted by ViSP classes.
Definition: vpException.h:59
const char * what() const
Definition: vpException.cpp:70
Implementation of an homogeneous matrix and operations on such kind of matrices.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:143
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
Definition of the vpImage class member functions.
Definition: vpImage.h:69
unsigned int getWidth() const
Definition: vpImage.h:245
unsigned int getHeight() const
Definition: vpImage.h:184
static std::string getViSPImagesDataPath()
Definition: vpIoTools.cpp:1832
static std::string createFilePath(const std::string &parent, const std::string &child)
Definition: vpIoTools.cpp:2195
Class that allows keypoints detection (and descriptors extraction) and matching thanks to OpenCV libr...
Definition: vpKeyPoint.h:212
static void compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpPolygon > &polygons, const std::vector< std::vector< vpPoint > > &roisPt, std::vector< cv::Point3f > &points, cv::Mat *descriptors=nullptr)
Definition: vpKeyPoint.cpp:460
static double rad(double deg)
Definition: vpMath.h:127
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:323
static double getStdev(const std::vector< double > &v, bool useBesselCorrection=false)
Definition: vpMath.cpp:354
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:303
Make the complete tracking of an object by using its CAD model.
virtual void setNearClippingDistance(const double &dist) vp_override
virtual void setFarClippingDistance(const double &dist) vp_override
virtual void loadConfigFile(const std::string &configFile, bool verbose=true) vp_override
virtual void setClipping(const unsigned int &flags) vp_override
virtual void setCameraParameters(const vpCameraParameters &cam) vp_override
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false) vp_override
void setMovingEdge(const vpMe &me)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo) vp_override
virtual void getCameraParameters(vpCameraParameters &cam) const
Definition: vpMbTracker.h:248
virtual void getPose(vpHomogeneousMatrix &cMo) const
Definition: vpMbTracker.h:414
virtual void setAngleDisappear(const double &a)
Definition: vpMbTracker.h:481
virtual void initClick(const vpImage< unsigned char > &I, const std::string &initFile, bool displayHelp=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
virtual void initFromPose(const vpImage< unsigned char > &I, const std::string &initFile)
virtual void loadModel(const std::string &modelFile, bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
virtual void setAngleAppear(const double &a)
Definition: vpMbTracker.h:470
virtual std::pair< std::vector< vpPolygon >, std::vector< std::vector< vpPoint > > > getPolygonFaces(bool orderPolygons=true, bool useVisibility=true, bool clipPolygon=false)
virtual unsigned int getClipping() const
Definition: vpMbTracker.h:256
Definition: vpMe.h:124
void setMu1(const double &mu_1)
Definition: vpMe.h:399
void setRange(const unsigned int &range)
Definition: vpMe.h:429
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition: vpMe.h:519
void setNbTotalSample(const int &ntotal_sample)
Definition: vpMe.h:413
void setMaskNumber(const unsigned int &mask_number)
Definition: vpMe.cpp:488
void setThreshold(const double &threshold)
Definition: vpMe.h:480
void setSampleStep(const double &sample_step)
Definition: vpMe.h:436
void setMaskSize(const unsigned int &mask_size)
Definition: vpMe.cpp:496
void setMu2(const double &mu_2)
Definition: vpMe.h:406
@ NORMALIZED_THRESHOLD
Definition: vpMe.h:135
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:69
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
void acquire(vpImage< vpRGBa > &I)
void open(vpImage< vpRGBa > &I)
void setFileName(const std::string &filename)
long getFrameIndex() const
void display(vpImage< unsigned char > &I, const std::string &title)
Display a gray-scale image.