MRPT  1.9.9
tracking.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "vision-precomp.h" // Precompiled headers
11 
12 #include <mrpt/vision/tracking.h>
14 
15 // Universal include for all versions of OpenCV
16 #include <mrpt/otherlibs/do_opencv_includes.h>
17 
18 using namespace mrpt;
19 using namespace mrpt::vision;
20 using namespace mrpt::img;
21 using namespace mrpt::tfest;
22 using namespace mrpt::math;
23 using namespace std;
24 
25 // ------------------------------- internal helper templates
26 // ---------------------------------
27 namespace mrpt::vision::detail
28 {
29 
30 template <typename FEATLIST>
32  FEATLIST& featureList, const CImage& cur_gray,
33  const float minimum_KLT_response, const unsigned int KLT_response_half_win,
34  const unsigned int max_x, const unsigned int max_y);
35 
36 template <>
38  CFeatureList& featureList, const CImage& cur_gray,
39  const float minimum_KLT_response, const unsigned int KLT_response_half_win,
40  const unsigned int max_x, const unsigned int max_y)
41 {
42  const CFeatureList::iterator itFeatEnd = featureList.end();
43  for (CFeatureList::iterator itFeat = featureList.begin();
44  itFeat != itFeatEnd; ++itFeat)
45  {
46  CFeature* ft = itFeat->get();
47  if (ft->track_status != status_TRACKED)
48  continue; // Skip if it's not correctly tracked.
49 
50  const unsigned int x = ft->x;
51  const unsigned int y = ft->y;
52  if (x > KLT_response_half_win && y > KLT_response_half_win &&
53  x < max_x && y < max_y)
54  { // Update response:
55  ft->response = cur_gray.KLT_response(x, y, KLT_response_half_win);
56 
57  // Is it good enough?
58  // http://grooveshark.com/s/Goonies+Are+Good+Enough/2beBfO?src=5
59  if (ft->response < minimum_KLT_response)
60  { // Nope!
62  }
63  }
64  else
65  { // Out of bounds
66  ft->response = 0;
68  }
69  }
70 } // end of trackFeatures_checkResponses<>
71 
72 template <class FEAT_LIST>
74  FEAT_LIST& featureList, const CImage& cur_gray,
75  const float minimum_KLT_response, const unsigned int KLT_response_half_win,
76  const unsigned int max_x_, const unsigned int max_y_)
77 {
78  if (featureList.empty()) return;
79 
80  using pixel_coord_t = typename FEAT_LIST::feature_t::pixel_coord_t;
81  const pixel_coord_t half_win =
82  static_cast<pixel_coord_t>(KLT_response_half_win);
83  const pixel_coord_t max_x = static_cast<pixel_coord_t>(max_x_);
84  const pixel_coord_t max_y = static_cast<pixel_coord_t>(max_y_);
85 
86  for (int N = featureList.size() - 1; N >= 0; --N)
87  {
88  typename FEAT_LIST::feature_t& ft = featureList[N];
89  if (ft.track_status != status_TRACKED)
90  continue; // Skip if it's not correctly tracked.
91 
92  if (ft.pt.x > half_win && ft.pt.y > half_win && ft.pt.x < max_x &&
93  ft.pt.y < max_y)
94  { // Update response:
95  ft.response =
96  cur_gray.KLT_response(ft.pt.x, ft.pt.y, KLT_response_half_win);
97 
98  // Is it good enough?
99  // http://grooveshark.com/s/Goonies+Are+Good+Enough/2beBfO?src=5
100  if (ft.response < minimum_KLT_response)
101  { // Nope!
102  ft.track_status = status_LOST;
103  }
104  }
105  else
106  { // Out of bounds
107  ft.response = 0;
108  ft.track_status = status_OOB;
109  }
110  }
111 } // end of trackFeatures_checkResponses<>
112 
113 template <>
115  TSimpleFeatureList& featureList, const CImage& cur_gray,
116  const float minimum_KLT_response, const unsigned int KLT_response_half_win,
117  const unsigned int max_x, const unsigned int max_y)
118 {
119  trackFeatures_checkResponses_impl_simple<TSimpleFeatureList>(
120  featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
121  max_x, max_y);
122 }
123 template <>
125  TSimpleFeaturefList& featureList, const CImage& cur_gray,
126  const float minimum_KLT_response, const unsigned int KLT_response_half_win,
127  const unsigned int max_x, const unsigned int max_y)
128 {
129  trackFeatures_checkResponses_impl_simple<TSimpleFeaturefList>(
130  featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
131  max_x, max_y);
132 }
133 
134 template <typename FEATLIST>
135 inline void trackFeatures_updatePatch(
136  FEATLIST& featureList, const CImage& cur_gray);
137 
138 template <>
140  CFeatureList& featureList, const CImage& cur_gray)
141 {
142  for (CFeatureList::iterator itFeat = featureList.begin();
143  itFeat != featureList.end(); ++itFeat)
144  {
145  CFeature* ft = itFeat->get();
146  if (ft->track_status != status_TRACKED)
147  continue; // Skip if it's not correctly tracked.
148 
149  const size_t patch_width = ft->patch.getWidth();
150  const size_t patch_height = ft->patch.getHeight();
151  if (patch_width > 0 && patch_height > 0)
152  {
153  try
154  {
155  const int offset = (int)patch_width / 2; // + 1;
156  cur_gray.extract_patch(
157  ft->patch, round(ft->x) - offset, round(ft->y) - offset,
158  patch_width, patch_height);
159  }
160  catch (std::exception&)
161  {
162  ft->track_status = status_OOB; // Out of bounds!
163  }
164  }
165  }
166 } // end of trackFeatures_updatePatch<>
167 template <>
169  TSimpleFeatureList& featureList, const CImage& cur_gray)
170 {
171  MRPT_UNUSED_PARAM(featureList);
172  MRPT_UNUSED_PARAM(cur_gray);
173  // This list type does not have patch stored explicitly
174 } // end of trackFeatures_updatePatch<>
175 template <>
177  TSimpleFeaturefList& featureList, const CImage& cur_gray)
178 {
179  MRPT_UNUSED_PARAM(featureList);
180  MRPT_UNUSED_PARAM(cur_gray);
181  // This list type does not have patch stored explicitly
182 } // end of trackFeatures_updatePatch<>
183 
184 template <typename FEATLIST>
185 inline void trackFeatures_addNewFeats(
186  FEATLIST& featureList, const TSimpleFeatureList& new_feats,
187  const std::vector<size_t>& sorted_indices, const size_t nNewToCheck,
188  const size_t maxNumFeatures, const float minimum_KLT_response_to_add,
189  const double threshold_sqr_dist_to_add_new, const size_t patchSize,
190  const CImage& cur_gray, TFeatureID& max_feat_ID_at_input);
191 
192 template <>
194  CFeatureList& featureList, const TSimpleFeatureList& new_feats,
195  const std::vector<size_t>& sorted_indices, const size_t nNewToCheck,
196  const size_t maxNumFeatures, const float minimum_KLT_response_to_add,
197  const double threshold_sqr_dist_to_add_new, const size_t patchSize,
198  const CImage& cur_gray, TFeatureID& max_feat_ID_at_input)
199 {
200  const TImageSize imgSize = cur_gray.getSize();
201  const int offset = (int)patchSize / 2 + 1;
202  const int w_off = int(imgSize.x - offset);
203  const int h_off = int(imgSize.y - offset);
204 
205  for (size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
206  i++)
207  {
208  const TSimpleFeature& feat = new_feats[sorted_indices[i]];
209 
210  if (feat.response < minimum_KLT_response_to_add) continue;
211 
212  double min_dist_sqr = square(10000);
213 
214  if (!featureList.empty())
215  {
216  // m_timlog.enter("[CGenericFeatureTracker] add new
217  // features.kdtree");
218  min_dist_sqr =
219  featureList.kdTreeClosestPoint2DsqrError(feat.pt.x, feat.pt.y);
220  // m_timlog.leave("[CGenericFeatureTracker] add new
221  // features.kdtree");
222  }
223 
224  if (min_dist_sqr > threshold_sqr_dist_to_add_new &&
225  feat.pt.x > offset && feat.pt.y > offset && feat.pt.x < w_off &&
226  feat.pt.y < h_off)
227  {
228  // Add new feature:
229  CFeature::Ptr ft = mrpt::make_aligned_shared<CFeature>();
230  ft->type = featFAST;
231  ft->ID = ++max_feat_ID_at_input;
232  ft->x = feat.pt.x;
233  ft->y = feat.pt.y;
234  ft->response = feat.response;
235  ft->orientation = 0;
236  ft->scale = 1;
237  ft->patchSize = patchSize; // The size of the feature patch
238 
239  if (patchSize > 0)
240  cur_gray.extract_patch(
241  ft->patch, round(ft->x) - offset, round(ft->y) - offset,
242  patchSize,
243  patchSize); // Image patch surronding the feature
244 
245  featureList.push_back(ft);
246  }
247  }
248 } // end of trackFeatures_addNewFeats<>
249 
250 template <class FEAT_LIST>
252  FEAT_LIST& featureList, const TSimpleFeatureList& new_feats,
253  const std::vector<size_t>& sorted_indices, const size_t nNewToCheck,
254  const size_t maxNumFeatures, const float minimum_KLT_response_to_add,
255  const double threshold_sqr_dist_to_add_new, const size_t patchSize,
256  const CImage& cur_gray, TFeatureID& max_feat_ID_at_input)
257 {
258 #if 0
259  // Brute-force version:
260  const int max_manhatan_dist = std::sqrt(2*threshold_sqr_dist_to_add_new);
261 
262  for (size_t i=0;i<nNewToCheck && featureList.size()<maxNumFeatures;i++)
263  {
264  const TSimpleFeature &feat = new_feats[ sorted_indices[i] ];
265  if (feat.response<minimum_KLT_response_to_add) break; // continue;
266 
267  // Check the min-distance:
268  int manh_dist = std::numeric_limits<int>::max();
269  for (size_t j=0;j<featureList.size();j++)
270  {
271  const TSimpleFeature &existing = featureList[j];
272  const int d = std::abs(existing.pt.x-feat.pt.x)+std::abs(existing.pt.y-feat.pt.y);
273  mrpt::keep_min(manh_dist, d);
274  }
275 
276  if (manh_dist<max_manhatan_dist)
277  continue; // Already occupied! skip.
278 
279  // OK: accept it
280  featureList.push_back_fast(feat.pt.x,feat.pt.y); // (x,y)
281  //featureList.mark_kdtree_as_outdated();
282 
283  // Fill out the rest of data:
284  TSimpleFeature &newFeat = featureList.back();
285 
286  newFeat.ID = ++max_feat_ID_at_input;
287  newFeat.response = feat.response;
288  newFeat.octave = 0;
289  /** Inactive: right after detection, and before being tried to track */
290  newFeat.track_status = status_IDLE;
291  }
292 #elif 0
293  // Version with an occupancy grid:
294  const int grid_cell_log2 = round(
295  std::log(std::sqrt(threshold_sqr_dist_to_add_new) * 0.5) /
296  std::log(2.0));
297 
298  int grid_lx = 1 + (cur_gray.getWidth() >> grid_cell_log2);
299  int grid_ly = 1 + (cur_gray.getHeight() >> grid_cell_log2);
300 
301  mrpt::math::CMatrixBool& occupied_sections =
302  featureList.getOccupiedSectionsMatrix();
303 
304  occupied_sections.setSize(
305  grid_lx, grid_ly); // See the comments above for an explanation.
306  occupied_sections.fillAll(false);
307 
308  for (size_t i = 0; i < featureList.size(); i++)
309  {
310  const TSimpleFeature& feat = featureList[i];
311  const int section_idx_x = feat.pt.x >> grid_cell_log2;
312  const int section_idx_y = feat.pt.y >> grid_cell_log2;
313 
314  if (!section_idx_x || !section_idx_y || section_idx_x >= grid_lx - 1 ||
315  section_idx_y >= grid_ly - 1)
316  continue; // This may be too radical, but speeds up the logic
317  // below...
318 
319  // Mark sections as occupied
320  bool* ptr1 =
321  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y - 1);
322  bool* ptr2 =
323  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y);
324  bool* ptr3 =
325  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y + 1);
326  ptr1[0] = ptr1[1] = ptr1[2] = true;
327  ptr2[0] = ptr2[1] = ptr2[2] = true;
328  ptr3[0] = ptr3[1] = ptr3[2] = true;
329  }
330 
331  for (size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
332  i++)
333  {
334  const TSimpleFeature& feat = new_feats[sorted_indices[i]];
335  if (feat.response < minimum_KLT_response_to_add) break; // continue;
336 
337  // Check the min-distance:
338  const int section_idx_x = feat.pt.x >> grid_cell_log2;
339  const int section_idx_y = feat.pt.y >> grid_cell_log2;
340 
341  if (!section_idx_x || !section_idx_y || section_idx_x >= grid_lx - 2 ||
342  section_idx_y >= grid_ly - 2)
343  continue; // This may be too radical, but speeds up the logic
344  // below...
345 
346  if (occupied_sections(section_idx_x, section_idx_y))
347  continue; // Already occupied! skip.
348 
349  // Mark section as occupied
350  bool* ptr1 =
351  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y - 1);
352  bool* ptr2 =
353  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y);
354  bool* ptr3 =
355  &occupied_sections.get_unsafe(section_idx_x - 1, section_idx_y + 1);
356 
357  ptr1[0] = ptr1[1] = ptr1[2] = true;
358  ptr2[0] = ptr2[1] = ptr2[2] = true;
359  ptr3[0] = ptr3[1] = ptr3[2] = true;
360 
361  // OK: accept it
362  featureList.push_back_fast(feat.pt.x, feat.pt.y); // (x,y)
363  // featureList.mark_kdtree_as_outdated();
364 
365  // Fill out the rest of data:
366  TSimpleFeature& newFeat = featureList.back();
367 
368  newFeat.ID = ++max_feat_ID_at_input;
369  newFeat.response = feat.response;
370  newFeat.octave = 0;
371  /** Inactive: right after detection, and before being tried to track */
372  newFeat.track_status = status_IDLE;
373  }
374 #else
375  MRPT_UNUSED_PARAM(patchSize);
376  MRPT_UNUSED_PARAM(cur_gray);
377  // Version with KD-tree
379  featureList.getVector());
380 
381  for (size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
382  i++)
383  {
384  const TSimpleFeature& feat = new_feats[sorted_indices[i]];
385  if (feat.response < minimum_KLT_response_to_add) break; // continue;
386 
387  // Check the min-distance:
388  double min_dist_sqr = std::numeric_limits<double>::max();
389 
390  if (!featureList.empty())
391  {
392  // m_timlog.enter("[CGenericFeatureTracker] add new
393  // features.kdtree");
394  min_dist_sqr =
395  kdtree.kdTreeClosestPoint2DsqrError(feat.pt.x, feat.pt.y);
396  // m_timlog.leave("[CGenericFeatureTracker] add new
397  // features.kdtree");
398  }
399 
400  if (min_dist_sqr > threshold_sqr_dist_to_add_new)
401  {
402  // OK: accept it
403  featureList.push_back_fast(feat.pt.x, feat.pt.y); // (x,y)
404  kdtree.mark_as_outdated();
405 
406  // Fill out the rest of data:
407  typename FEAT_LIST::feature_t& newFeat = featureList.back();
408 
409  newFeat.ID = ++max_feat_ID_at_input;
410  newFeat.response = feat.response;
411  newFeat.octave = 0;
412  /** Inactive: right after detection, and before being tried to track
413  */
414  newFeat.track_status = status_IDLE;
415  }
416  }
417 
418 #endif
419 } // end of trackFeatures_addNewFeats<>
420 
421 template <>
423  TSimpleFeatureList& featureList, const TSimpleFeatureList& new_feats,
424  const std::vector<size_t>& sorted_indices, const size_t nNewToCheck,
425  const size_t maxNumFeatures, const float minimum_KLT_response_to_add,
426  const double threshold_sqr_dist_to_add_new, const size_t patchSize,
427  const CImage& cur_gray, TFeatureID& max_feat_ID_at_input)
428 {
429  trackFeatures_addNewFeats_simple_list<TSimpleFeatureList>(
430  featureList, new_feats, sorted_indices, nNewToCheck, maxNumFeatures,
431  minimum_KLT_response_to_add, threshold_sqr_dist_to_add_new, patchSize,
432  cur_gray, max_feat_ID_at_input);
433 }
434 template <>
436  TSimpleFeaturefList& featureList, const TSimpleFeatureList& new_feats,
437  const std::vector<size_t>& sorted_indices, const size_t nNewToCheck,
438  const size_t maxNumFeatures, const float minimum_KLT_response_to_add,
439  const double threshold_sqr_dist_to_add_new, const size_t patchSize,
440  const CImage& cur_gray, TFeatureID& max_feat_ID_at_input)
441 {
442  trackFeatures_addNewFeats_simple_list<TSimpleFeaturefList>(
443  featureList, new_feats, sorted_indices, nNewToCheck, maxNumFeatures,
444  minimum_KLT_response_to_add, threshold_sqr_dist_to_add_new, patchSize,
445  cur_gray, max_feat_ID_at_input);
446 }
447 
448 // Return the number of removed features
449 template <typename FEATLIST>
450 inline size_t trackFeatures_deleteOOB(
451  FEATLIST& trackedFeats, const size_t img_width, const size_t img_height,
452  const int MIN_DIST_MARGIN_TO_STOP_TRACKING);
453 
454 template <typename FEATLIST>
456  FEATLIST& trackedFeats, const size_t img_width, const size_t img_height,
457  const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
458 {
459  if (trackedFeats.empty()) return 0;
460 
461  std::vector<size_t> survival_idxs;
462  const size_t N = trackedFeats.size();
463 
464  // 1st: Build list of survival indexes:
465  survival_idxs.reserve(N);
466  for (size_t i = 0; i < N; i++)
467  {
468  const typename FEATLIST::feature_t& ft = trackedFeats[i];
469  const TFeatureTrackStatus status = ft.track_status;
470  bool eras = (status_TRACKED != status && status_IDLE != status);
471  if (!eras)
472  {
473  // Also, check if it's too close to the image border:
474  const int x = ft.pt.x;
475  const int y = ft.pt.y;
476  if (x < MIN_DIST_MARGIN_TO_STOP_TRACKING ||
477  y < MIN_DIST_MARGIN_TO_STOP_TRACKING ||
478  x > static_cast<int>(
479  img_width - MIN_DIST_MARGIN_TO_STOP_TRACKING) ||
480  y > static_cast<int>(
481  img_height - MIN_DIST_MARGIN_TO_STOP_TRACKING))
482  {
483  eras = true;
484  }
485  }
486  if (!eras) survival_idxs.push_back(i);
487  }
488 
489  // 2nd: Build updated list:
490  const size_t N2 = survival_idxs.size();
491  const size_t n_removed = N - N2;
492  for (size_t i = 0; i < N2; i++)
493  {
494  if (survival_idxs[i] != i)
495  trackedFeats[i] = trackedFeats[survival_idxs[i]];
496  }
497  trackedFeats.resize(N2);
498  return n_removed;
499 } // end of trackFeatures_deleteOOB
500 
501 template <>
503  TSimpleFeatureList& trackedFeats, const size_t img_width,
504  const size_t img_height, const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
505 {
506  return trackFeatures_deleteOOB_impl_simple_feat<TSimpleFeatureList>(
507  trackedFeats, img_width, img_height, MIN_DIST_MARGIN_TO_STOP_TRACKING);
508 }
509 template <>
511  TSimpleFeaturefList& trackedFeats, const size_t img_width,
512  const size_t img_height, const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
513 {
514  return trackFeatures_deleteOOB_impl_simple_feat<TSimpleFeaturefList>(
515  trackedFeats, img_width, img_height, MIN_DIST_MARGIN_TO_STOP_TRACKING);
516 }
517 
518 template <>
520  CFeatureList& trackedFeats, const size_t img_width, const size_t img_height,
521  const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
522 {
523  CFeatureList::iterator itFeat = trackedFeats.begin();
524  size_t n_removed = 0;
525  while (itFeat != trackedFeats.end())
526  {
527  const TFeatureTrackStatus status = (*itFeat)->track_status;
528  bool eras = (status_TRACKED != status && status_IDLE != status);
529  if (!eras)
530  {
531  // Also, check if it's too close to the image border:
532  const float x = (*itFeat)->x;
533  const float y = (*itFeat)->y;
534  if (x < MIN_DIST_MARGIN_TO_STOP_TRACKING ||
535  y < MIN_DIST_MARGIN_TO_STOP_TRACKING ||
536  x > (img_width - MIN_DIST_MARGIN_TO_STOP_TRACKING) ||
537  y > (img_height - MIN_DIST_MARGIN_TO_STOP_TRACKING))
538  {
539  eras = true;
540  }
541  }
542  if (eras) // Erase or keep?
543  {
544  itFeat = trackedFeats.erase(itFeat);
545  n_removed++;
546  }
547  else
548  ++itFeat;
549  }
550  return n_removed;
551 } // end of trackFeatures_deleteOOB
552 } // end NS's
553 // ---------------------------- end of internal helper templates
554 // -------------------------------
555 
557  const CImage& old_img, const CImage& new_img,
558  TSimpleFeaturefList& inout_featureList)
559 {
560  MRPT_UNUSED_PARAM(old_img);
561  MRPT_UNUSED_PARAM(new_img);
562  MRPT_UNUSED_PARAM(inout_featureList);
563  THROW_EXCEPTION("Method not implemented by derived class!");
564 }
565 
566 /** Perform feature tracking from "old_img" to "new_img", with a (possibly
567  *empty) list of previously tracked features "featureList".
568  * This is a list of parameters (in "extraParams") accepted by ALL
569  *implementations of feature tracker (see each derived class for more specific
570  *parameters).
571  * - "add_new_features" (Default=0). If set to "1", new features will be
572  *also
573  *added to the existing ones in areas of the image poor of features.
574  * This method actually first call the pure virtual "trackFeatures_impl"
575  *method, then implements the optional detection of new features if
576  *"add_new_features"!=0.
577  */
578 template <typename FEATLIST>
580  const CImage& old_img, const CImage& new_img, FEATLIST& featureList)
581 {
582  m_timlog.enter(
583  "[CGenericFeatureTracker::trackFeatures] Complete iteration");
584 
585  const size_t img_width = new_img.getWidth();
586  const size_t img_height = new_img.getHeight();
587 
588  // Take the maximum ID of "old" features so new feats (if
589  // "add_new_features==true") will be id+1, id+2, ...
590  TFeatureID max_feat_ID_at_input = 0;
591  if (!featureList.empty()) max_feat_ID_at_input = featureList.getMaxID();
592 
593  // Grayscale images
594  // =========================================
595  m_timlog.enter("[CGenericFeatureTracker] Convert grayscale");
596 
597  const CImage prev_gray(old_img, FAST_REF_OR_CONVERT_TO_GRAY);
598  const CImage cur_gray(new_img, FAST_REF_OR_CONVERT_TO_GRAY);
599 
600  m_timlog.leave("[CGenericFeatureTracker] Convert grayscale");
601 
602  // =================================
603  // (1st STEP) Do the actual tracking
604  // =================================
605  m_newly_detected_feats.clear();
606 
607  m_timlog.enter("[CGenericFeatureTracker] trackFeatures_impl");
608 
609  trackFeatures_impl(prev_gray, cur_gray, featureList);
610 
611  m_timlog.leave("[CGenericFeatureTracker] trackFeatures_impl");
612 
613  // ========================================================
614  // (2nd STEP) For successfully followed features, check their KLT response??
615  // ========================================================
616  const int check_KLT_response_every =
617  extra_params.getWithDefaultVal("check_KLT_response_every", 0);
618  const float minimum_KLT_response =
619  extra_params.getWithDefaultVal("minimum_KLT_response", 5);
620  const unsigned int KLT_response_half_win =
621  extra_params.getWithDefaultVal("KLT_response_half_win", 4);
622 
623  if (check_KLT_response_every > 0 &&
624  ++m_check_KLT_counter >= size_t(check_KLT_response_every))
625  {
626  m_timlog.enter("[CGenericFeatureTracker] check KLT responses");
627  m_check_KLT_counter = 0;
628 
629  const unsigned int max_x = img_width - KLT_response_half_win;
630  const unsigned int max_y = img_height - KLT_response_half_win;
631 
633  featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
634  max_x, max_y);
635 
636  m_timlog.leave("[CGenericFeatureTracker] check KLT responses");
637 
638  } // end check_KLT_response_every
639 
640  // ============================================================
641  // (3rd STEP) Remove Out-of-bounds or badly tracked features
642  // or those marked as "bad" by their low KLT response
643  // ============================================================
644  const bool remove_lost_features =
645  extra_params.getWithDefaultVal("remove_lost_features", 0) != 0;
646 
647  if (remove_lost_features)
648  {
649  m_timlog.enter("[CGenericFeatureTracker] removal of OOB");
650 
651  static const int MIN_DIST_MARGIN_TO_STOP_TRACKING = 10;
652 
653  const size_t nRemoved = detail::trackFeatures_deleteOOB(
654  featureList, img_width, img_height,
655  MIN_DIST_MARGIN_TO_STOP_TRACKING);
656 
657  m_timlog.leave("[CGenericFeatureTracker] removal of OOB");
658 
659  last_execution_extra_info.num_deleted_feats = nRemoved;
660  }
661  else
662  {
663  last_execution_extra_info.num_deleted_feats = 0;
664  }
665 
666  // ========================================================
667  // (4th STEP) For successfully followed features, update its patch:
668  // ========================================================
669  const int update_patches_every =
670  extra_params.getWithDefaultVal("update_patches_every", 0);
671 
672  if (update_patches_every > 0 &&
673  ++m_update_patches_counter >= size_t(update_patches_every))
674  {
675  m_timlog.enter("[CGenericFeatureTracker] update patches");
676  m_update_patches_counter = 0;
677 
678  // Update the patch for each valid feature:
679  detail::trackFeatures_updatePatch(featureList, cur_gray);
680 
681  m_timlog.leave("[CGenericFeatureTracker] update patches");
682  } // end if update_patches_every
683 
684  // ========================================================
685  // (5th STEP) Do detection of new features??
686  // ========================================================
687  const bool add_new_features =
688  extra_params.getWithDefaultVal("add_new_features", 0) != 0;
689  const double threshold_dist_to_add_new =
690  extra_params.getWithDefaultVal("add_new_feat_min_separation", 15);
691 
692  // Additional operation: if "add_new_features==true", find new features and
693  // add them in
694  // areas spare of valid features:
695  if (add_new_features)
696  {
697  m_timlog.enter("[CGenericFeatureTracker] add new features");
698 
699  // Look for new features and save in "m_newly_detected_feats", if
700  // they're not already computed:
701  if (m_newly_detected_feats.empty())
702  {
703  // Do the detection
705  cur_gray, m_newly_detected_feats, m_detector_adaptive_thres);
706  }
707 
708  const size_t N = m_newly_detected_feats.size();
709 
710  last_execution_extra_info.raw_FAST_feats_detected =
711  N; // Extra out info.
712 
713  // Update the adaptive threshold.
714  const size_t desired_num_features = extra_params.getWithDefaultVal(
715  "desired_num_features_adapt",
716  size_t((img_width * img_height) >> 9));
717  updateAdaptiveNewFeatsThreshold(N, desired_num_features);
718 
719  // Use KLT response instead of the OpenCV's original "response" field:
720  {
721  const unsigned int max_x = img_width - KLT_response_half_win;
722  const unsigned int max_y = img_height - KLT_response_half_win;
723  for (size_t i = 0; i < N; i++)
724  {
725  const unsigned int x = m_newly_detected_feats[i].pt.x;
726  const unsigned int y = m_newly_detected_feats[i].pt.y;
727  if (x > KLT_response_half_win && y > KLT_response_half_win &&
728  x < max_x && y < max_y)
729  m_newly_detected_feats[i].response =
730  cur_gray.KLT_response(x, y, KLT_response_half_win);
731  else
732  m_newly_detected_feats[i].response = 0; // Out of bounds
733  }
734  }
735 
736  // Sort them by "response": It's ~100 times faster to sort a list of
737  // indices "sorted_indices" than sorting directly the actual list
738  // of features "m_newly_detected_feats"
739  std::vector<size_t> sorted_indices(N);
740  for (size_t i = 0; i < N; i++) sorted_indices[i] = i;
741 
742  std::sort(
743  sorted_indices.begin(), sorted_indices.end(),
744  KeypointResponseSorter<TSimpleFeatureList>(m_newly_detected_feats));
745 
746  // For each new good feature, add it to the list of tracked ones only if
747  // it's pretty
748  // isolated:
749 
750  const size_t nNewToCheck = std::min(size_t(1500), N);
751  const double threshold_sqr_dist_to_add_new =
752  square(threshold_dist_to_add_new);
753  const size_t maxNumFeatures =
754  extra_params.getWithDefaultVal("add_new_feat_max_features", 100);
755  const size_t patchSize =
756  extra_params.getWithDefaultVal("add_new_feat_patch_size", 11);
757 
758  const float minimum_KLT_response_to_add =
759  extra_params.getWithDefaultVal("minimum_KLT_response_to_add", 10);
760 
761  // Do it:
763  featureList, m_newly_detected_feats, sorted_indices, nNewToCheck,
764  maxNumFeatures, minimum_KLT_response_to_add,
765  threshold_sqr_dist_to_add_new, patchSize, cur_gray,
766  max_feat_ID_at_input);
767 
768  m_timlog.leave("[CGenericFeatureTracker] add new features");
769  }
770 
771  m_timlog.leave(
772  "[CGenericFeatureTracker::trackFeatures] Complete iteration");
773 
774 } // end of CGenericFeatureTracker::trackFeatures
775 
777  const CImage& old_img, const CImage& new_img, CFeatureList& featureList)
778 {
779  internal_trackFeatures<CFeatureList>(old_img, new_img, featureList);
780 }
781 
783  const CImage& old_img, const CImage& new_img,
784  TSimpleFeatureList& featureList)
785 {
786  internal_trackFeatures<TSimpleFeatureList>(old_img, new_img, featureList);
787 }
788 
790  const CImage& old_img, const CImage& new_img,
791  TSimpleFeaturefList& featureList)
792 {
793  internal_trackFeatures<TSimpleFeaturefList>(old_img, new_img, featureList);
794 }
795 
797  const size_t nNewlyDetectedFeats, const size_t desired_num_features)
798 {
799  const size_t hysteresis_min_num_feats = desired_num_features * 0.9;
800  const size_t hysteresis_max_num_feats = desired_num_features * 1.1;
801 
802  if (nNewlyDetectedFeats < hysteresis_min_num_feats)
803  m_detector_adaptive_thres = std::max(
804  2.0, std::min(
805  m_detector_adaptive_thres - 1.0,
806  m_detector_adaptive_thres * 0.8));
807  else if (nNewlyDetectedFeats > hysteresis_max_num_feats)
808  m_detector_adaptive_thres = std::max(
809  m_detector_adaptive_thres + 1.0, m_detector_adaptive_thres * 1.2);
810 }
811 
812 /*------------------------------------------------------------
813  checkTrackedFeatures
814 -------------------------------------------------------------*/
816  CFeatureList& leftList, CFeatureList& rightList,
817  vision::TMatchingOptions options)
818 {
819  ASSERT_(leftList.size() == rightList.size());
820 
821  // std::cout << std::endl << "Tracked features checking ..." << std::endl;
822 
823  CFeatureList::iterator itLeft, itRight;
824  size_t u, v;
825  double res;
826 
827  for (itLeft = leftList.begin(), itRight = rightList.begin();
828  itLeft != leftList.end();)
829  {
830  bool delFeat = false;
831  if ((*itLeft)->x < 0 || (*itLeft)->y < 0 || // Out of bounds
832  (*itRight)->x < 0 || (*itRight)->y < 0 || // Out of bounds
833  fabs((*itLeft)->y - (*itRight)->y) >
834  options
835  .epipolar_TH) // Not fulfillment of the epipolar constraint
836  {
837  // Show reason
838  std::cout << "Bad tracked match:";
839  if ((*itLeft)->x < 0 || (*itLeft)->y < 0 || (*itRight)->x < 0 ||
840  (*itRight)->y < 0)
841  std::cout << " Out of bounds: (" << (*itLeft)->x << ","
842  << (*itLeft)->y << " & (" << (*itRight)->x << ","
843  << (*itRight)->y << ")" << std::endl;
844 
845  if (fabs((*itLeft)->y - (*itRight)->y) > options.epipolar_TH)
846  std::cout << " Bad row checking: "
847  << fabs((*itLeft)->y - (*itRight)->y) << std::endl;
848 
849  delFeat = true;
850  }
851  else
852  {
853  // Compute cross correlation:
855  (*itLeft)->patch, (*itRight)->patch, u, v, res);
856 
857  if (res < options.minCC_TH)
858  {
859  std::cout << "Bad tracked match (correlation failed):"
860  << " CC Value: " << res << std::endl;
861  delFeat = true;
862  }
863  } // end if
864 
865  if (delFeat) // Erase the pair of features
866  {
867  itLeft = leftList.erase(itLeft);
868  itRight = rightList.erase(itRight);
869  }
870  else
871  {
872  itLeft++;
873  itRight++;
874  }
875  } // end for
876 } // end checkTrackedFeatures
877 
878 /*-------------------------------------------------------------
879  filterBadCorrsByDistance
880 -------------------------------------------------------------*/
882  TMatchingPairList& feat_list, unsigned int numberOfSigmas)
883 {
884  ASSERT_(numberOfSigmas > 0);
885  // MRPT_UNUSED_PARAM( numberOfSigmas );
886  MRPT_START
887 
889  CMatrix dist;
890  double v_mean, v_std;
891  unsigned int count = 0;
892 
893  dist.setSize(feat_list.size(), 1);
894  // v_mean.resize(1);
895  // v_std.resize(1);
896 
897  // Compute mean and standard deviation of the distance
898  for (itPair = feat_list.begin(); itPair != feat_list.end();
899  itPair++, count++)
900  {
901  // cout << "(" << itPair->other_x << "," << itPair->other_y << "," <<
902  // itPair->this_z << ")" << "- (" << itPair->this_x << "," <<
903  // itPair->this_y << "," << itPair->other_z << "): ";
904  // cout << sqrt( square( itPair->other_x - itPair->this_x ) + square(
905  // itPair->other_y - itPair->this_y ) + square( itPair->other_z -
906  // itPair->this_z ) ) << endl;
907  dist(count, 0) = sqrt(
908  square(itPair->other_x - itPair->this_x) +
909  square(itPair->other_y - itPair->this_y) +
910  square(itPair->other_z - itPair->this_z));
911  }
912 
913  dist.meanAndStdAll(v_mean, v_std);
914 
915  cout << endl
916  << "*****************************************************" << endl;
917  cout << "Mean: " << v_mean << " - STD: " << v_std << endl;
918  cout << endl
919  << "*****************************************************" << endl;
920 
921  // Filter out bad points
922  unsigned int idx = 0;
923  // for( int idx = (int)feat_list.size()-1; idx >= 0; idx-- )
924  for (itPair = feat_list.begin(); itPair != feat_list.end(); idx++)
925  {
926  // if( dist( idx, 0 ) > 1.2 )
927  if (fabs(dist(idx, 0) - v_mean) > v_std * numberOfSigmas)
928  {
929  cout << "Outlier deleted: " << dist(idx, 0) << " vs "
930  << v_std * numberOfSigmas << endl;
931  itPair = feat_list.erase(itPair);
932  }
933  else
934  itPair++;
935  }
936 
937  MRPT_END
938 } // end filterBadCorrsByDistance
void trackFeatures_addNewFeats(FEATLIST &featureList, const TSimpleFeatureList &new_feats, const std::vector< size_t > &sorted_indices, const size_t nNewToCheck, const size_t maxNumFeatures, const float minimum_KLT_response_to_add, const double threshold_sqr_dist_to_add_new, const size_t patchSize, const CImage &cur_gray, TFeatureID &max_feat_ID_at_input)
const T & get_unsafe(size_t row, size_t col) const
Fast but unsafe method to read a value from the matrix.
Scalar * iterator
Definition: eigen_plugins.h:26
GLuint GLuint GLsizei count
Definition: glext.h:3528
Helper class: KD-tree search class for vector<KeyPoint>: Call mark_as_outdated() to force rebuilding ...
#define MRPT_START
Definition: exceptions.h:262
uint64_t TFeatureID
Definition of a feature ID.
#define min(a, b)
Declares a matrix of booleans (non serializable).
void trackFeatures_updatePatch< TSimpleFeaturefList >(TSimpleFeaturefList &featureList, const CImage &cur_gray)
Definition: tracking.cpp:176
TInternalFeatList::iterator iterator
Definition: CFeature.h:365
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
size_t trackFeatures_deleteOOB_impl_simple_feat(FEATLIST &trackedFeats, const size_t img_width, const size_t img_height, const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
Definition: tracking.cpp:455
TFeatureTrackStatus track_status
featKLT, featHarris, featSURF, featBeacon
Definition: CFeature.h:68
void internal_trackFeatures(const mrpt::img::CImage &old_img, const mrpt::img::CImage &new_img, FEATLIST &inout_featureList)
Perform feature tracking from "old_img" to "new_img", with a (possibly empty) list of previously trac...
Definition: tracking.cpp:579
size_t size() const
Definition: CFeature.h:386
GLintptr offset
Definition: glext.h:3925
size_t getHeight() const override
Returns the height of the image in pixels.
Definition: CImage.cpp:892
STL namespace.
float epipolar_TH
Epipolar constraint (rows of pixels)
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
float y
Coordinates in the image.
Definition: CFeature.h:61
TFeatureTrackStatus track_status
Status of the feature tracking process.
void trackFeatures_checkResponses_impl_simple(FEAT_LIST &featureList, const CImage &cur_gray, const float minimum_KLT_response, const unsigned int KLT_response_half_win, const unsigned int max_x_, const unsigned int max_y_)
Definition: tracking.cpp:73
virtual void trackFeatures_impl(const mrpt::img::CImage &old_img, const mrpt::img::CImage &new_img, TSimpleFeaturefList &inout_featureList)
The tracking method implementation, to be implemented in children classes.
Definition: tracking.cpp:556
FAST feature detector, OpenCV&#39;s implementation ("Faster and better: A machine learning approach to...
Inactive (right after detection, and before being tried to track)
A helper struct to sort keypoints by their response: It can be used with these types: ...
T square(const T x)
Inline function for the square of a number.
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:113
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
Definition: CImage.cpp:864
void trackFeatures_addNewFeats< TSimpleFeaturefList >(TSimpleFeaturefList &featureList, const TSimpleFeatureList &new_feats, const std::vector< size_t > &sorted_indices, const size_t nNewToCheck, const size_t maxNumFeatures, const float minimum_KLT_response_to_add, const double threshold_sqr_dist_to_add_new, const size_t patchSize, const CImage &cur_gray, TFeatureID &max_feat_ID_at_input)
Definition: tracking.cpp:435
void trackFeatures_updatePatch< TSimpleFeatureList >(TSimpleFeatureList &featureList, const CImage &cur_gray)
Definition: tracking.cpp:168
A list of TMatchingPair.
Definition: TMatchingPair.h:81
void updateAdaptiveNewFeatsThreshold(const size_t nNewlyDetectedFeats, const size_t desired_num_features)
Adapts the threshold m_detector_adaptive_thres according to the real and desired number of features j...
Definition: tracking.cpp:796
A pair (x,y) of pixel coordinates (integer resolution).
Definition: TPixelCoord.h:37
void trackFeatures_addNewFeats< TSimpleFeatureList >(TSimpleFeatureList &featureList, const TSimpleFeatureList &new_feats, const std::vector< size_t > &sorted_indices, const size_t nNewToCheck, const size_t maxNumFeatures, const float minimum_KLT_response_to_add, const double threshold_sqr_dist_to_add_new, const size_t patchSize, const CImage &cur_gray, TFeatureID &max_feat_ID_at_input)
Definition: tracking.cpp:422
Classes for computer vision, detectors, features, etc.
Definition: CCamModel.h:18
A generic 2D feature from an image, extracted with CFeatureExtraction Each feature may have one or mo...
Definition: CFeature.h:53
void trackFeatures(const mrpt::img::CImage &old_img, const mrpt::img::CImage &new_img, TSimpleFeatureList &inout_featureList)
Perform feature tracking from "old_img" to "new_img", with a (possibly empty) list of previously trac...
Definition: tracking.cpp:782
uint8_t octave
The image octave the image was found in: 0=original image, 1=1/2 image, 2=1/4 image, etc.
iterator erase(const iterator &it)
Definition: CFeature.h:379
static void detectFeatures_SSE2_FASTER12(const mrpt::img::CImage &img, TSimpleFeatureList &corners, const int threshold=20, bool append_to_list=false, uint8_t octave=0, std::vector< size_t > *out_feats_index_by_row=nullptr)
Just like detectFeatures_SSE2_FASTER9() for another version of the detector.
A list of visual features, to be used as output by detectors, as input/output by trackers, etc.
Definition: CFeature.h:304
Unable to track this feature (mismatch is too high for the given tracking window: lack of texture...
void checkTrackedFeatures(CFeatureList &leftList, CFeatureList &rightList, vision::TMatchingOptions options)
Search for correspondences which are not in the same row and deletes them ...
Definition: tracking.cpp:815
float response
process (old name: KLT_status)
Definition: CFeature.h:70
const GLdouble * v
Definition: glext.h:3678
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void trackFeatures_addNewFeats< CFeatureList >(CFeatureList &featureList, const TSimpleFeatureList &new_feats, const std::vector< size_t > &sorted_indices, const size_t nNewToCheck, const size_t maxNumFeatures, const float minimum_KLT_response_to_add, const double threshold_sqr_dist_to_add_new, const size_t patchSize, const CImage &cur_gray, TFeatureID &max_feat_ID_at_input)
Definition: tracking.cpp:193
void trackFeatures_checkResponses(FEATLIST &featureList, const CImage &cur_gray, const float minimum_KLT_response, const unsigned int KLT_response_half_win, const unsigned int max_x, const unsigned int max_y)
void trackFeatures_addNewFeats_simple_list(FEAT_LIST &featureList, const TSimpleFeatureList &new_feats, const std::vector< size_t > &sorted_indices, const size_t nNewToCheck, const size_t maxNumFeatures, const float minimum_KLT_response_to_add, const double threshold_sqr_dist_to_add_new, const size_t patchSize, const CImage &cur_gray, TFeatureID &max_feat_ID_at_input)
Definition: tracking.cpp:251
TFeatureID ID
ID of the feature.
float KLT_response(const unsigned int x, const unsigned int y, const unsigned int half_window_size) const
Compute the KLT response at a given pixel (x,y) - Only for grayscale images (for efficiency it avoids...
Definition: CImage.cpp:2593
void filterBadCorrsByDistance(mrpt::tfest::TMatchingPairList &list, unsigned int numberOfSigmas)
Filter bad correspondences by distance ...
Definition: tracking.cpp:881
size_t trackFeatures_deleteOOB(FEATLIST &trackedFeats, const size_t img_width, const size_t img_height, const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
pixel_coords_t pt
Coordinates in the image.
float response
A measure of the "goodness" of the feature (typically, the KLT_response value)
#define MRPT_END
Definition: exceptions.h:266
A structure containing options for the matching.
A simple structure for representing one image feature (without descriptor nor patch) - This is the te...
void trackFeatures_updatePatch< CFeatureList >(CFeatureList &featureList, const CImage &cur_gray)
Definition: tracking.cpp:139
_u8 status
Definition: rplidar_cmd.h:19
GLenum GLint GLint y
Definition: glext.h:3538
float minCC_TH
Minimum Value of the Cross Correlation.
void setSize(size_t row, size_t col, bool zeroNewElements=false)
Changes the size of matrix, maintaining the previous contents.
void trackFeatures_checkResponses< CFeatureList >(CFeatureList &featureList, const CImage &cur_gray, const float minimum_KLT_response, const unsigned int KLT_response_half_win, const unsigned int max_x, const unsigned int max_y)
Definition: tracking.cpp:37
void trackFeatures_checkResponses< TSimpleFeatureList >(TSimpleFeatureList &featureList, const CImage &cur_gray, const float minimum_KLT_response, const unsigned int KLT_response_half_win, const unsigned int max_x, const unsigned int max_y)
Definition: tracking.cpp:114
GLuint res
Definition: glext.h:7268
GLenum GLint x
Definition: glext.h:3538
void openCV_cross_correlation(const mrpt::img::CImage &img, const mrpt::img::CImage &patch_img, size_t &x_max, size_t &y_max, double &max_val, int x_search_ini=-1, int y_search_ini=-1, int x_search_size=-1, int y_search_size=-1)
Computes the correlation between this image and another one, encapsulating the openCV function cvMatc...
Feature fell Out Of Bounds (out of the image limits, too close to image borders)
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:22
mrpt::img::CImage patch
A patch of the image surrounding the feature.
Definition: CFeature.h:63
Functions for estimating the optimal transformation between two frames of references given measuremen...
void trackFeatures_updatePatch(FEATLIST &featureList, const CImage &cur_gray)
size_t trackFeatures_deleteOOB(CFeatureList &trackedFeats, const size_t img_width, const size_t img_height, const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
Definition: tracking.cpp:519
void trackFeatures_checkResponses< TSimpleFeaturefList >(TSimpleFeaturefList &featureList, const CImage &cur_gray, const float minimum_KLT_response, const unsigned int KLT_response_half_win, const unsigned int max_x, const unsigned int max_y)
Definition: tracking.cpp:124
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
void fillAll(const T &val)
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186
int round(const T value)
Returns the closer integer (int) to x.
Definition: round.h:23



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020