Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpMbDepthDenseTracker.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Model-based tracker using depth dense features.
33  *
34 *****************************************************************************/
35 
36 #include <iostream>
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
41 #include <pcl/point_cloud.h>
42 #endif
43 
44 #include <visp3/core/vpDisplay.h>
45 #include <visp3/core/vpExponentialMap.h>
46 #include <visp3/core/vpTrackingException.h>
47 #include <visp3/mbt/vpMbDepthDenseTracker.h>
48 #include <visp3/mbt/vpMbtXmlGenericParser.h>
49 
50 #if DEBUG_DISPLAY_DEPTH_DENSE
51 #include <visp3/gui/vpDisplayGDI.h>
52 #include <visp3/gui/vpDisplayX.h>
53 #endif
54 
57  : m_depthDenseHiddenFacesDisplay(), m_depthDenseListOfActiveFaces(), m_denseDepthNbFeatures(0), m_depthDenseFaces(),
58  m_depthDenseSamplingStepX(2), m_depthDenseSamplingStepY(2), m_error_depthDense(), m_L_depthDense(),
59  m_robust_depthDense(), m_w_depthDense(), m_weightedError_depthDense()
60 #if DEBUG_DISPLAY_DEPTH_DENSE
61  ,
62  m_debugDisp_depthDense(nullptr), m_debugImage_depthDense()
63 #endif
64 {
65 #ifdef VISP_HAVE_OGRE
66  faces.getOgreContext()->setWindowName("MBT Depth Dense");
67 #endif
68 
69 #if defined(VISP_HAVE_X11) && DEBUG_DISPLAY_DEPTH_DENSE
70  m_debugDisp_depthDense = new vpDisplayX;
71 #elif defined(VISP_HAVE_GDI) && DEBUG_DISPLAY_DEPTH_DENSE
72  m_debugDisp_depthDense = new vpDisplayGDI;
73 #endif
74 }
75 
77 {
78  for (size_t i = 0; i < m_depthDenseFaces.size(); i++) {
79  delete m_depthDenseFaces[i];
80  }
81 
82 #if DEBUG_DISPLAY_DEPTH_DENSE
83  delete m_debugDisp_depthDense;
84 #endif
85 }
86 
87 void vpMbDepthDenseTracker::addFace(vpMbtPolygon &polygon, bool alreadyClose)
88 {
89  if (polygon.nbpt < 3) {
90  return;
91  }
92 
93  // Copy hidden faces
95 
96  vpMbtFaceDepthDense *normal_face = new vpMbtFaceDepthDense;
97  normal_face->m_hiddenFace = &faces;
98  normal_face->m_polygon = &polygon;
99  normal_face->m_cam = m_cam;
100  normal_face->m_useScanLine = useScanLine;
101  normal_face->m_clippingFlag = clippingFlag;
102  normal_face->m_distNearClip = distNearClip;
103  normal_face->m_distFarClip = distFarClip;
104 
105  // Add lines that compose the face
106  unsigned int nbpt = polygon.getNbPoint();
107  if (nbpt > 0) {
108  for (unsigned int i = 0; i < nbpt - 1; i++) {
109  normal_face->addLine(polygon.p[i], polygon.p[i + 1], &m_depthDenseHiddenFacesDisplay, m_rand, polygon.getIndex(),
110  polygon.getName());
111  }
112 
113  if (!alreadyClose) {
114  // Add last line that closes the face
115  normal_face->addLine(polygon.p[nbpt - 1], polygon.p[0], &m_depthDenseHiddenFacesDisplay, m_rand,
116  polygon.getIndex(), polygon.getName());
117  }
118  }
119 
120  // Construct a vpPlane in object frame
121  vpPoint pts[3];
122  pts[0] = polygon.p[0];
123  pts[1] = polygon.p[1];
124  pts[2] = polygon.p[2];
125  normal_face->m_planeObject = vpPlane(pts[0], pts[1], pts[2], vpPlane::object_frame);
126 
127  m_depthDenseFaces.push_back(normal_face);
128 }
129 
130 void vpMbDepthDenseTracker::computeVisibility(unsigned int width, unsigned int height)
131 {
132  bool changed = false;
133  faces.setVisible(width, height, m_cam, m_cMo, angleAppears, angleDisappears, changed);
134 
135  if (useScanLine) {
136  // if (clippingFlag <= 2) {
137  // cam.computeFov(width, height);
138  // }
139 
141  faces.computeScanLineRender(m_cam, width, height);
142  }
143 
144  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
145  ++it) {
146  vpMbtFaceDepthDense *face_normal = *it;
147  face_normal->computeVisibility();
148  }
149 }
150 
152 {
153  double normRes = 0;
154  double normRes_1 = -1;
155  unsigned int iter = 0;
156 
157  computeVVSInit();
158 
160  vpMatrix LTL;
161  vpColVector LTR, v;
162 
163  double mu = m_initialMu;
164  vpHomogeneousMatrix cMo_prev;
165 
166  bool isoJoIdentity = m_isoJoIdentity; // Backup since it can be modified if L is not full rank
167  if (isoJoIdentity)
168  oJo.eye();
169 
171  vpMatrix L_true, LVJ_true;
172 
173  while (std::fabs(normRes_1 - normRes) > m_stopCriteriaEpsilon && (iter < m_maxIter)) {
175 
176  bool reStartFromLastIncrement = false;
177  computeVVSCheckLevenbergMarquardt(iter, m_error_depthDense, error_prev, cMo_prev, mu, reStartFromLastIncrement);
178 
179  if (!reStartFromLastIncrement) {
181 
182  if (computeCovariance) {
183  L_true = m_L_depthDense;
184  if (!isoJoIdentity) {
185  cVo.build(m_cMo);
186  LVJ_true = (m_L_depthDense * cVo * oJo);
187  }
188  }
189 
190  // Compute DoF only once
191  if (iter == 0) {
192  // If all the 6 dof should be estimated, we check if the interaction
193  // matrix is full rank. If not we remove automatically the dof that
194  // cannot be estimated. This is particularly useful when considering
195  // circles (rank 5) and cylinders (rank 4)
196  if (isoJoIdentity) {
197  cVo.build(m_cMo);
198 
199  vpMatrix K; // kernel
200  unsigned int rank = (m_L_depthDense * cVo).kernel(K);
201  if (rank == 0) {
202  throw vpException(vpException::fatalError, "Rank=0, cannot estimate the pose !");
203  }
204 
205  if (rank != 6) {
206  vpMatrix I; // Identity
207  I.eye(6);
208  oJo = I - K.AtA();
209 
210  isoJoIdentity = false;
211  }
212  }
213  }
214 
215  double num = 0.0, den = 0.0;
216  for (unsigned int i = 0; i < m_L_depthDense.getRows(); i++) {
217  // Compute weighted errors and stop criteria
220  den += m_w_depthDense[i];
221 
222  // weight interaction matrix
223  for (unsigned int j = 0; j < 6; j++) {
224  m_L_depthDense[i][j] *= m_w_depthDense[i];
225  }
226  }
227 
229  m_error_depthDense, error_prev, LTR, mu, v);
230 
231  cMo_prev = m_cMo;
233 
234  normRes_1 = normRes;
235  normRes = sqrt(num / den);
236  }
237 
238  iter++;
239  }
240 
241  computeCovarianceMatrixVVS(isoJoIdentity, m_w_depthDense, cMo_prev, L_true, LVJ_true, m_error_depthDense);
242 }
243 
245 {
247 
248  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseListOfActiveFaces.begin();
249  it != m_depthDenseListOfActiveFaces.end(); ++it) {
250  vpMbtFaceDepthDense *face = *it;
252  }
253 
254  m_L_depthDense.resize(m_denseDepthNbFeatures, 6, false, false);
257 
259  m_w_depthDense = 1;
260 }
261 
263 {
264  unsigned int start_index = 0;
265  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseListOfActiveFaces.begin();
266  it != m_depthDenseListOfActiveFaces.end(); ++it) {
267  vpMbtFaceDepthDense *face = *it;
268 
269  vpMatrix L_face;
270  vpColVector error;
271 
272  face->computeInteractionMatrixAndResidu(m_cMo, L_face, error);
273 
274  m_error_depthDense.insert(start_index, error);
275  m_L_depthDense.insert(L_face, start_index, 0);
276 
277  start_index += error.getRows();
278  }
279 }
280 
282 {
284 }
285 
287  const vpCameraParameters &cam, const vpColor &col, unsigned int thickness,
288  bool displayFullModel)
289 {
290  std::vector<std::vector<double> > models =
291  vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel);
292 
293  for (size_t i = 0; i < models.size(); i++) {
294  if (vpMath::equal(models[i][0], 0)) {
295  vpImagePoint ip1(models[i][1], models[i][2]);
296  vpImagePoint ip2(models[i][3], models[i][4]);
297  vpDisplay::displayLine(I, ip1, ip2, col, thickness);
298  }
299  }
300 }
301 
303  const vpCameraParameters &cam, const vpColor &col, unsigned int thickness,
304  bool displayFullModel)
305 {
306  std::vector<std::vector<double> > models =
307  vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel);
308 
309  for (size_t i = 0; i < models.size(); i++) {
310  if (vpMath::equal(models[i][0], 0)) {
311  vpImagePoint ip1(models[i][1], models[i][2]);
312  vpImagePoint ip2(models[i][3], models[i][4]);
313  vpDisplay::displayLine(I, ip1, ip2, col, thickness);
314  }
315  }
316 }
317 
333 std::vector<std::vector<double> > vpMbDepthDenseTracker::getModelForDisplay(unsigned int width, unsigned int height,
334  const vpHomogeneousMatrix &cMo,
335  const vpCameraParameters &cam,
336  bool displayFullModel)
337 {
338  std::vector<std::vector<double> > models;
339 
340  vpCameraParameters c = cam;
341 
342  bool changed = false;
343  m_depthDenseHiddenFacesDisplay.setVisible(width, height, c, cMo, angleAppears, angleDisappears, changed);
344 
345  if (useScanLine) {
346  c.computeFov(width, height);
347 
350  }
351 
352  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
353  ++it) {
354  vpMbtFaceDepthDense *face_dense = *it;
355  std::vector<std::vector<double> > modelLines =
356  face_dense->getModelForDisplay(width, height, cMo, cam, displayFullModel);
357  models.insert(models.end(), modelLines.begin(), modelLines.end());
358  }
359 
360  return models;
361 }
362 
364 {
365  if (!modelInitialised) {
366  throw vpException(vpException::fatalError, "model not initialized");
367  }
368 
369  bool reInitialisation = false;
370  if (!useOgre) {
371  faces.setVisible(I.getWidth(), I.getHeight(), m_cam, m_cMo, angleAppears, angleDisappears, reInitialisation);
372  }
373  else {
374 #ifdef VISP_HAVE_OGRE
375  if (!faces.isOgreInitialised()) {
379  // Turn off Ogre config dialog display for the next call to this
380  // function since settings are saved in the ogre.cfg file and used
381  // during the next call
382  ogreShowConfigDialog = false;
383  }
384 
386 #else
387  faces.setVisible(I.getWidth(), I.getHeight(), m_cam, m_cMo, angleAppears, angleDisappears, reInitialisation);
388 #endif
389  }
390 
391  if (useScanLine || clippingFlag > 3)
393 
395 }
396 
397 void vpMbDepthDenseTracker::loadConfigFile(const std::string &configFile, bool verbose)
398 {
399 #if defined(VISP_HAVE_PUGIXML)
401  xmlp.setVerbose(verbose);
405 
408 
409  try {
410  if (verbose) {
411  std::cout << " *********** Parsing XML for Mb Depth Dense Tracker ************ " << std::endl;
412  }
413  xmlp.parse(configFile);
414  }
415  catch (const vpException &e) {
416  std::cerr << "Exception: " << e.what() << std::endl;
417  throw vpException(vpException::ioError, "Cannot open XML file \"%s\"", configFile.c_str());
418  }
419 
420  vpCameraParameters camera;
421  xmlp.getCameraParameters(camera);
422  setCameraParameters(camera);
423 
426 
427  if (xmlp.hasNearClippingDistance())
429 
430  if (xmlp.hasFarClippingDistance())
432 
433  if (xmlp.getFovClipping())
435 
437 #else
438  (void)configFile;
439  (void)verbose;
440  throw(vpException(vpException::ioError, "vpMbDepthDenseTracker::loadConfigFile() needs pugixml built-in 3rdparty"));
441 #endif
442 }
443 
444 void vpMbDepthDenseTracker::reInitModel(const vpImage<unsigned char> &I, const std::string &cad_name,
445  const vpHomogeneousMatrix &cMo, bool verbose)
446 {
447  m_cMo.eye();
448 
449  for (size_t i = 0; i < m_depthDenseFaces.size(); i++) {
450  delete m_depthDenseFaces[i];
451  m_depthDenseFaces[i] = nullptr;
452  }
453 
454  m_depthDenseFaces.clear();
455 
456  loadModel(cad_name, verbose);
457  initFromPose(I, cMo);
458 }
459 
460 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
461 void vpMbDepthDenseTracker::reInitModel(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &point_cloud,
462  const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose)
463 {
464  vpImage<unsigned char> I_dummy(point_cloud->height, point_cloud->width);
465  reInitModel(I_dummy, cad_name, cMo, verbose);
466 }
467 
468 #endif
469 
471 {
472  m_cMo.eye();
473 
474  for (std::vector<vpMbtFaceDepthDense *>::iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
475  ++it) {
476  vpMbtFaceDepthDense *normal_face = *it;
477  delete normal_face;
478  normal_face = nullptr;
479  }
480 
481  m_depthDenseFaces.clear();
482 
483  m_computeInteraction = true;
484  computeCovariance = false;
485 
488 
490 
491  m_lambda = 1.0;
492  m_maxIter = 30;
493 
494  faces.reset();
495 
497 
498  useScanLine = false;
499 
500 #ifdef VISP_HAVE_OGRE
501  useOgre = false;
502 #endif
503 
505 }
506 
508 {
509  m_cam = cam;
510 
511  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
512  ++it) {
513  (*it)->setCameraParameters(cam);
514  }
515 }
516 
518 {
519  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
520  ++it) {
521  (*it)->setDepthDenseFilteringMaxDistance(maxDistance);
522  }
523 }
524 
526 {
527  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
528  ++it) {
529  (*it)->setDepthDenseFilteringMethod(method);
530  }
531 }
532 
534 {
535  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
536  ++it) {
537  (*it)->setDepthDenseFilteringMinDistance(minDistance);
538  }
539 }
540 
542 {
543  if (occupancyRatio < 0.0 || occupancyRatio > 1.0) {
544  std::cerr << "occupancyRatio < 0.0 || occupancyRatio > 1.0" << std::endl;
545  return;
546  }
547 
548  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
549  ++it) {
550  (*it)->setDepthDenseFilteringOccupancyRatio(occupancyRatio);
551  }
552 }
553 
554 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
555 void vpMbDepthDenseTracker::segmentPointCloud(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &point_cloud)
556 {
558 
559 #if DEBUG_DISPLAY_DEPTH_DENSE
560  if (!m_debugDisp_depthDense->isInitialised()) {
561  m_debugImage_depthDense.resize(point_cloud->height, point_cloud->width);
562  m_debugDisp_depthDense->init(m_debugImage_depthDense, 50, 0, "Debug display dense depth tracker");
563  }
564 
565  m_debugImage_depthDense = 0;
566  std::vector<std::vector<vpImagePoint> > roiPts_vec;
567 #endif
568 
569  for (std::vector<vpMbtFaceDepthDense *>::iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
570  ++it) {
571  vpMbtFaceDepthDense *face = *it;
572 
573  if (face->isVisible() && face->isTracked()) {
574 #if DEBUG_DISPLAY_DEPTH_DENSE
575  std::vector<std::vector<vpImagePoint> > roiPts_vec_;
576 #endif
578 #if DEBUG_DISPLAY_DEPTH_DENSE
579  ,
580  m_debugImage_depthDense, roiPts_vec_
581 #endif
582  ,
583  m_mask)) {
584  m_depthDenseListOfActiveFaces.push_back(*it);
585 
586 #if DEBUG_DISPLAY_DEPTH_DENSE
587  roiPts_vec.insert(roiPts_vec.end(), roiPts_vec_.begin(), roiPts_vec_.end());
588 #endif
589  }
590  }
591  }
592 
593 #if DEBUG_DISPLAY_DEPTH_DENSE
594  vpDisplay::display(m_debugImage_depthDense);
595 
596  for (size_t i = 0; i < roiPts_vec.size(); i++) {
597  if (roiPts_vec[i].empty())
598  continue;
599 
600  for (size_t j = 0; j < roiPts_vec[i].size() - 1; j++) {
601  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][j], roiPts_vec[i][j + 1], vpColor::red, 2);
602  }
603  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][0], roiPts_vec[i][roiPts_vec[i].size() - 1],
604  vpColor::red, 2);
605  }
606 
607  vpDisplay::flush(m_debugImage_depthDense);
608 #endif
609 }
610 #endif
611 
612 void vpMbDepthDenseTracker::segmentPointCloud(const std::vector<vpColVector> &point_cloud, unsigned int width,
613  unsigned int height)
614 {
616 
617 #if DEBUG_DISPLAY_DEPTH_DENSE
618  if (!m_debugDisp_depthDense->isInitialised()) {
619  m_debugImage_depthDense.resize(height, width);
620  m_debugDisp_depthDense->init(m_debugImage_depthDense, 50, 0, "Debug display dense depth tracker");
621  }
622 
623  m_debugImage_depthDense = 0;
624  std::vector<std::vector<vpImagePoint> > roiPts_vec;
625 #endif
626 
627  for (std::vector<vpMbtFaceDepthDense *>::iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
628  ++it) {
629  vpMbtFaceDepthDense *face = *it;
630 
631  if (face->isVisible() && face->isTracked()) {
632 #if DEBUG_DISPLAY_DEPTH_DENSE
633  std::vector<std::vector<vpImagePoint> > roiPts_vec_;
634 #endif
635  if (face->computeDesiredFeatures(m_cMo, width, height, point_cloud, m_depthDenseSamplingStepX,
637 #if DEBUG_DISPLAY_DEPTH_DENSE
638  ,
639  m_debugImage_depthDense, roiPts_vec_
640 #endif
641  ,
642  m_mask)) {
643  m_depthDenseListOfActiveFaces.push_back(*it);
644 
645 #if DEBUG_DISPLAY_DEPTH_DENSE
646  roiPts_vec.insert(roiPts_vec.end(), roiPts_vec_.begin(), roiPts_vec_.end());
647 #endif
648  }
649  }
650  }
651 
652 #if DEBUG_DISPLAY_DEPTH_DENSE
653  vpDisplay::display(m_debugImage_depthDense);
654 
655  for (size_t i = 0; i < roiPts_vec.size(); i++) {
656  if (roiPts_vec[i].empty())
657  continue;
658 
659  for (size_t j = 0; j < roiPts_vec[i].size() - 1; j++) {
660  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][j], roiPts_vec[i][j + 1], vpColor::red, 2);
661  }
662  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][0], roiPts_vec[i][roiPts_vec[i].size() - 1],
663  vpColor::red, 2);
664  }
665 
666  vpDisplay::flush(m_debugImage_depthDense);
667 #endif
668 }
669 
670 
671 void vpMbDepthDenseTracker::segmentPointCloud(const vpMatrix &point_cloud, unsigned int width,
672  unsigned int height)
673 {
675 
676 #if DEBUG_DISPLAY_DEPTH_DENSE
677  if (!m_debugDisp_depthDense->isInitialised()) {
678  m_debugImage_depthDense.resize(height, width);
679  m_debugDisp_depthDense->init(m_debugImage_depthDense, 50, 0, "Debug display dense depth tracker");
680  }
681 
682  m_debugImage_depthDense = 0;
683  std::vector<std::vector<vpImagePoint> > roiPts_vec;
684 #endif
685 
686  for (std::vector<vpMbtFaceDepthDense *>::iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
687  ++it) {
688  vpMbtFaceDepthDense *face = *it;
689 
690  if (face->isVisible() && face->isTracked()) {
691 #if DEBUG_DISPLAY_DEPTH_DENSE
692  std::vector<std::vector<vpImagePoint> > roiPts_vec_;
693 #endif
694  if (face->computeDesiredFeatures(m_cMo, width, height, point_cloud, m_depthDenseSamplingStepX,
696 #if DEBUG_DISPLAY_DEPTH_DENSE
697  ,
698  m_debugImage_depthDense, roiPts_vec_
699 #endif
700  ,
701  m_mask)) {
702  m_depthDenseListOfActiveFaces.push_back(*it);
703 
704 #if DEBUG_DISPLAY_DEPTH_DENSE
705  roiPts_vec.insert(roiPts_vec.end(), roiPts_vec_.begin(), roiPts_vec_.end());
706 #endif
707  }
708  }
709  }
710 
711 #if DEBUG_DISPLAY_DEPTH_DENSE
712  vpDisplay::display(m_debugImage_depthDense);
713 
714  for (size_t i = 0; i < roiPts_vec.size(); i++) {
715  if (roiPts_vec[i].empty())
716  continue;
717 
718  for (size_t j = 0; j < roiPts_vec[i].size() - 1; j++) {
719  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][j], roiPts_vec[i][j + 1], vpColor::red, 2);
720  }
721  vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][0], roiPts_vec[i][roiPts_vec[i].size() - 1],
722  vpColor::red, 2);
723  }
724 
725  vpDisplay::flush(m_debugImage_depthDense);
726 #endif
727 }
728 
730 {
732 #ifdef VISP_HAVE_OGRE
733  faces.getOgreContext()->setWindowName("MBT Depth Dense");
734 #endif
735 }
736 
738 {
739  m_cMo = cdMo;
740  init(I);
741 }
742 
744 {
745  m_cMo = cdMo;
746  vpImageConvert::convert(I_color, m_I);
747  init(m_I);
748 }
749 
750 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
751 void vpMbDepthDenseTracker::setPose(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &point_cloud,
752  const vpHomogeneousMatrix &cdMo)
753 {
754  m_I.resize(point_cloud->height, point_cloud->width);
755  m_cMo = cdMo;
756  init(m_I);
757 }
758 #endif
759 
761 {
763 
764  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
765  ++it) {
766  (*it)->setScanLineVisibilityTest(v);
767  }
768 }
769 
770 void vpMbDepthDenseTracker::setUseDepthDenseTracking(const std::string &name, const bool &useDepthDenseTracking)
771 {
772  for (std::vector<vpMbtFaceDepthDense *>::const_iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end();
773  ++it) {
774  vpMbtFaceDepthDense *face = *it;
775  if (face->m_polygon->getName() == name) {
776  face->setTracked(useDepthDenseTracking);
777  }
778  }
779 }
780 
782 
784 {
785  throw vpException(vpException::fatalError, "Cannot track with a grayscale image!");
786 }
787 
789 {
790  throw vpException(vpException::fatalError, "Cannot track with a color image!");
791 }
792 
793 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
794 void vpMbDepthDenseTracker::track(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &point_cloud)
795 {
796  segmentPointCloud(point_cloud);
797 
798  computeVVS();
799 
800  computeVisibility(point_cloud->width, point_cloud->height);
801 }
802 #endif
803 
804 void vpMbDepthDenseTracker::track(const std::vector<vpColVector> &point_cloud, unsigned int width, unsigned int height)
805 {
806  segmentPointCloud(point_cloud, width, height);
807 
808  computeVVS();
809 
810  computeVisibility(width, height);
811 }
812 
813 void vpMbDepthDenseTracker::initCircle(const vpPoint & /*p1*/, const vpPoint & /*p2*/, const vpPoint & /*p3*/,
814  double /*radius*/, int /*idFace*/, const std::string & /*name*/)
815 {
816  throw vpException(vpException::fatalError, "vpMbDepthDenseTracker::initCircle() should not be called!");
817 }
818 
819 void vpMbDepthDenseTracker::initCylinder(const vpPoint & /*p1*/, const vpPoint & /*p2*/, double /*radius*/,
820  int /*idFace*/, const std::string & /*name*/)
821 {
822  throw vpException(vpException::fatalError, "vpMbDepthDenseTracker::initCylinder() should not be called!");
823 }
824 
826 
828 END_VISP_NAMESPACE
void setWindowName(const Ogre::String &n)
Definition: vpAROgre.h:265
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:362
unsigned int getRows() const
Definition: vpArray2D.h:347
Generic class defining intrinsic camera parameters.
void computeFov(const unsigned int &w, const unsigned int &h)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
void insert(unsigned int i, const vpColVector &v)
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
Class to define RGB colors available for display functionalities.
Definition: vpColor.h:157
static const vpColor red
Definition: vpColor.h:217
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:135
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void flush(const vpImage< unsigned char > &I)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ ioError
I/O error.
Definition: vpException.h:67
@ fatalError
Fatal error.
Definition: vpException.h:72
const char * what() const
Definition: vpException.cpp:71
static vpHomogeneousMatrix direct(const vpColVector &v)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
unsigned int getWidth() const
Definition: vpImage.h:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:538
unsigned int getHeight() const
Definition: vpImage.h:181
static double rad(double deg)
Definition: vpMath.h:129
static double sqr(double x)
Definition: vpMath.h:203
static bool equal(double x, double y, double threshold=0.001)
Definition: vpMath.h:458
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
vpMatrix AtA() const
void insert(const vpMatrix &A, unsigned int r, unsigned int c)
Definition: vpMatrix.cpp:1133
virtual void initFaceFromLines(vpMbtPolygon &polygon) VP_OVERRIDE
virtual void initFaceFromCorners(vpMbtPolygon &polygon) VP_OVERRIDE
void segmentPointCloud(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &point_cloud)
virtual std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false) VP_OVERRIDE
vpMbtTukeyEstimator< double > m_robust_depthDense
Tukey M-Estimator.
virtual void setScanLineVisibilityTest(const bool &v) VP_OVERRIDE
virtual void setDepthDenseFilteringMaxDistance(double maxDistance)
void computeVisibility(unsigned int width, unsigned int height)
virtual void setCameraParameters(const vpCameraParameters &camera) VP_OVERRIDE
virtual void setDepthDenseFilteringMethod(int method)
virtual void init(const vpImage< unsigned char > &I) VP_OVERRIDE
void reInitModel(const vpImage< unsigned char > &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose=false)
vpColVector m_weightedError_depthDense
Weighted error.
unsigned int m_depthDenseSamplingStepY
Sampling step in y-direction.
virtual ~vpMbDepthDenseTracker() VP_OVERRIDE
virtual void resetTracker() VP_OVERRIDE
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo) VP_OVERRIDE
vpMbHiddenFaces< vpMbtPolygon > m_depthDenseHiddenFacesDisplay
Set of faces describing the object used only for display with scan line.
virtual void testTracking() 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 setUseDepthDenseTracking(const std::string &name, const bool &useDepthDenseTracking)
unsigned int m_depthDenseSamplingStepX
Sampling step in x-direction.
vpColVector m_error_depthDense
(s - s*)
virtual void computeVVSInteractionMatrixAndResidu() VP_OVERRIDE
virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace=0, const std::string &name="") VP_OVERRIDE
vpMatrix m_L_depthDense
Interaction matrix.
std::vector< vpMbtFaceDepthDense * > m_depthDenseListOfActiveFaces
List of current active (visible and features extracted) faces.
virtual void computeVVSInit() VP_OVERRIDE
virtual void track(const vpImage< unsigned char > &) VP_OVERRIDE
void setDepthDenseSamplingStep(unsigned int stepX, unsigned int stepY)
void addFace(vpMbtPolygon &polygon, bool alreadyClose)
virtual void setOgreVisibilityTest(const bool &v) VP_OVERRIDE
virtual void setDepthDenseFilteringMinDistance(double minDistance)
unsigned int m_denseDepthNbFeatures
Nb features.
vpColVector m_w_depthDense
Robust weights.
virtual void loadConfigFile(const std::string &configFile, bool verbose=true) VP_OVERRIDE
virtual void setDepthDenseFilteringOccupancyRatio(double occupancyRatio)
virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace=0, const std::string &name="") VP_OVERRIDE
std::vector< vpMbtFaceDepthDense * > m_depthDenseFaces
List of faces.
vpAROgre * getOgreContext()
void computeClippedPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam)
unsigned int setVisibleOgre(unsigned int width, unsigned int height, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angleAppears, const double &angleDisappears, bool &changed)
void initOgre(const vpCameraParameters &cam=vpCameraParameters())
unsigned int setVisible(unsigned int width, unsigned int height, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angle, bool &changed)
void setBackgroundSizeOgre(const unsigned int &h, const unsigned int &w)
void computeScanLineRender(const vpCameraParameters &cam, const unsigned int &w, const unsigned int &h)
void setOgreShowConfigDialog(bool showConfigDialog)
double m_lambda
Gain of the virtual visual servoing stage.
Definition: vpMbTracker.h:189
bool modelInitialised
Definition: vpMbTracker.h:125
vpImage< unsigned char > m_I
Grayscale image buffer, used when passing color images.
Definition: vpMbTracker.h:225
bool m_computeInteraction
Definition: vpMbTracker.h:187
vpMatrix oJo
The Degrees of Freedom to estimate.
Definition: vpMbTracker.h:117
vpUniRand m_rand
Random number generator used in vpMbtDistanceLine::buildFrom()
Definition: vpMbTracker.h:229
double m_initialMu
Initial Mu for Levenberg Marquardt optimization loop.
Definition: vpMbTracker.h:195
vpHomogeneousMatrix m_cMo
The current pose.
Definition: vpMbTracker.h:115
virtual void computeVVSCheckLevenbergMarquardt(unsigned int iter, vpColVector &error, const vpColVector &m_error_prev, const vpHomogeneousMatrix &cMoPrev, double &mu, bool &reStartFromLastIncrement, vpColVector *const w=nullptr, const vpColVector *const m_w_prev=nullptr)
vpCameraParameters m_cam
The camera parameters.
Definition: vpMbTracker.h:113
double m_stopCriteriaEpsilon
Epsilon threshold to stop the VVS optimization loop.
Definition: vpMbTracker.h:193
bool useOgre
Use Ogre3d for visibility tests.
Definition: vpMbTracker.h:157
vpMbHiddenFaces< vpMbtPolygon > faces
Set of faces describing the object.
Definition: vpMbTracker.h:145
virtual void setScanLineVisibilityTest(const bool &v)
Definition: vpMbTracker.h:610
virtual void setOgreVisibilityTest(const bool &v)
virtual void computeCovarianceMatrixVVS(const bool isoJoIdentity, const vpColVector &w_true, const vpHomogeneousMatrix &cMoPrev, const vpMatrix &L_true, const vpMatrix &LVJ_true, const vpColVector &error)
vpMbtOptimizationMethod m_optimizationMethod
Optimization method used.
Definition: vpMbTracker.h:142
virtual void computeVVSPoseEstimation(const bool isoJoIdentity, unsigned int iter, vpMatrix &L, vpMatrix &LTL, vpColVector &R, const vpColVector &error, vpColVector &error_prev, vpColVector &LTR, double &mu, vpColVector &v, const vpColVector *const w=nullptr, vpColVector *const m_w_prev=nullptr)
double angleDisappears
Angle used to detect a face disappearance.
Definition: vpMbTracker.h:149
virtual void setNearClippingDistance(const double &dist)
virtual void setFarClippingDistance(const double &dist)
double distFarClip
Distance for near clipping.
Definition: vpMbTracker.h:153
bool m_isoJoIdentity
Boolean to know if oJo is identity (for fast computation)
Definition: vpMbTracker.h:119
bool useScanLine
Use Scanline for visibility tests.
Definition: vpMbTracker.h:160
virtual void setClipping(const unsigned int &flags)
double angleAppears
Angle used to detect a face appearance.
Definition: vpMbTracker.h:147
const vpImage< bool > * m_mask
Mask used to disable tracking on a part of image.
Definition: vpMbTracker.h:223
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())
bool computeCovariance
Flag used to specify if the covariance matrix has to be computed or not.
Definition: vpMbTracker.h:130
double distNearClip
Distance for near clipping.
Definition: vpMbTracker.h:151
unsigned int m_maxIter
Maximum number of iterations of the virtual visual servoing stage.
Definition: vpMbTracker.h:191
bool ogreShowConfigDialog
Definition: vpMbTracker.h:158
unsigned int clippingFlag
Flags specifying which clipping to used.
Definition: vpMbTracker.h:155
vpMbHiddenFaces< vpMbtPolygon > * m_hiddenFace
Pointer to the list of faces.
double m_distFarClip
Distance for near clipping.
vpPlane m_planeObject
Plane equation described in the object frame.
std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)
unsigned int getNbFeatures() const
void setTracked(bool tracked)
void computeInteractionMatrixAndResidu(const vpHomogeneousMatrix &cMo, vpMatrix &L, vpColVector &error)
vpMbtPolygon * m_polygon
Polygon defining the face.
bool m_useScanLine
Scan line visibility.
bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &point_cloud, unsigned int stepX, unsigned int stepY, const vpImage< bool > *mask=nullptr)
unsigned int m_clippingFlag
Flags specifying which clipping to used.
vpCameraParameters m_cam
Camera intrinsic parameters.
double m_distNearClip
Distance for near clipping.
void addLine(vpPoint &p1, vpPoint &p2, vpMbHiddenFaces< vpMbtPolygon > *const faces, vpUniRand &rand_gen, int polygon=-1, std::string name="")
Implementation of a polygon of the model used by the model-based tracker.
Definition: vpMbtPolygon.h:60
std::string getName() const
Definition: vpMbtPolygon.h:100
int getIndex() const
Definition: vpMbtPolygon.h:93
Parse an Xml file to extract configuration parameters of a mbtConfig object.
void getCameraParameters(vpCameraParameters &cam) const
void setDepthDenseSamplingStepY(unsigned int stepY)
void setAngleDisappear(const double &adisappear)
void setDepthDenseSamplingStepX(unsigned int stepX)
void setAngleAppear(const double &aappear)
unsigned int getDepthDenseSamplingStepY() const
void parse(const std::string &filename)
unsigned int getDepthDenseSamplingStepX() const
void setCameraParameters(const vpCameraParameters &cam)
This class defines the container for a plane geometrical structure.
Definition: vpPlane.h:57
@ object_frame
Definition: vpPlane.h:65
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
unsigned int nbpt
Number of points used to define the polygon.
Definition: vpPolygon3D.h:74
unsigned int getNbPoint() const
Definition: vpPolygon3D.h:130
vpPoint * p
corners in the object frame
Definition: vpPolygon3D.h:79
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)