16 #include <mrpt/otherlibs/do_opencv_includes.h> 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);
39 const float minimum_KLT_response,
const unsigned int KLT_response_half_win,
40 const unsigned int max_x,
const unsigned int max_y)
44 itFeat != itFeatEnd; ++itFeat)
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)
55 ft->
response = cur_gray.KLT_response(
x,
y, KLT_response_half_win);
59 if (ft->
response < minimum_KLT_response)
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_)
78 if (featureList.empty())
return;
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_);
86 for (
int N = featureList.size() - 1; N >= 0; --N)
88 typename FEAT_LIST::feature_t& ft = featureList[N];
92 if (ft.pt.x > half_win && ft.pt.y > half_win && ft.pt.x < max_x &&
96 cur_gray.
KLT_response(ft.pt.x, ft.pt.y, KLT_response_half_win);
100 if (ft.response < minimum_KLT_response)
116 const float minimum_KLT_response,
const unsigned int KLT_response_half_win,
117 const unsigned int max_x,
const unsigned int max_y)
119 trackFeatures_checkResponses_impl_simple<TSimpleFeatureList>(
120 featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
126 const float minimum_KLT_response,
const unsigned int KLT_response_half_win,
127 const unsigned int max_x,
const unsigned int max_y)
129 trackFeatures_checkResponses_impl_simple<TSimpleFeaturefList>(
130 featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
134 template <
typename FEATLIST>
136 FEATLIST& featureList,
const CImage& cur_gray);
143 itFeat != featureList.end(); ++itFeat)
151 if (patch_width > 0 && patch_height > 0)
155 const int offset = (int)patch_width / 2;
156 cur_gray.extract_patch(
158 patch_width, patch_height);
160 catch (std::exception&)
184 template <
typename FEATLIST>
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,
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,
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);
205 for (
size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
210 if (feat.
response < minimum_KLT_response_to_add)
continue;
212 double min_dist_sqr =
square(10000);
214 if (!featureList.empty())
219 featureList.kdTreeClosestPoint2DsqrError(feat.
pt.x, feat.
pt.y);
224 if (min_dist_sqr > threshold_sqr_dist_to_add_new &&
231 ft->ID = ++max_feat_ID_at_input;
237 ft->patchSize = patchSize;
240 cur_gray.extract_patch(
245 featureList.push_back(ft);
250 template <
class FEAT_LIST>
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,
260 const int max_manhatan_dist = std::sqrt(2*threshold_sqr_dist_to_add_new);
262 for (
size_t i=0;i<nNewToCheck && featureList.size()<maxNumFeatures;i++)
265 if (feat.
response<minimum_KLT_response_to_add)
break;
268 int manh_dist = std::numeric_limits<int>::max();
269 for (
size_t j=0;j<featureList.size();j++)
272 const int d = std::abs(existing.
pt.x-feat.
pt.x)+std::abs(existing.
pt.y-feat.
pt.y);
276 if (manh_dist<max_manhatan_dist)
280 featureList.push_back_fast(feat.
pt.x,feat.
pt.y);
286 newFeat.
ID = ++max_feat_ID_at_input;
294 const int grid_cell_log2 =
round(
295 std::log(std::sqrt(threshold_sqr_dist_to_add_new) * 0.5) /
298 int grid_lx = 1 + (cur_gray.
getWidth() >> grid_cell_log2);
299 int grid_ly = 1 + (cur_gray.
getHeight() >> grid_cell_log2);
302 featureList.getOccupiedSectionsMatrix();
306 occupied_sections.
fillAll(
false);
308 for (
size_t i = 0; i < featureList.size(); 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;
314 if (!section_idx_x || !section_idx_y || section_idx_x >= grid_lx - 1 ||
315 section_idx_y >= grid_ly - 1)
321 &occupied_sections.
get_unsafe(section_idx_x - 1, section_idx_y - 1);
323 &occupied_sections.
get_unsafe(section_idx_x - 1, section_idx_y);
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;
331 for (
size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
335 if (feat.
response < minimum_KLT_response_to_add)
break;
338 const int section_idx_x = feat.
pt.x >> grid_cell_log2;
339 const int section_idx_y = feat.
pt.y >> grid_cell_log2;
341 if (!section_idx_x || !section_idx_y || section_idx_x >= grid_lx - 2 ||
342 section_idx_y >= grid_ly - 2)
346 if (occupied_sections(section_idx_x, section_idx_y))
351 &occupied_sections.
get_unsafe(section_idx_x - 1, section_idx_y - 1);
353 &occupied_sections.
get_unsafe(section_idx_x - 1, section_idx_y);
355 &occupied_sections.
get_unsafe(section_idx_x - 1, section_idx_y + 1);
357 ptr1[0] = ptr1[1] = ptr1[2] =
true;
358 ptr2[0] = ptr2[1] = ptr2[2] =
true;
359 ptr3[0] = ptr3[1] = ptr3[2] =
true;
362 featureList.push_back_fast(feat.
pt.x, feat.
pt.y);
368 newFeat.
ID = ++max_feat_ID_at_input;
379 featureList.getVector());
381 for (
size_t i = 0; i < nNewToCheck && featureList.size() < maxNumFeatures;
385 if (feat.
response < minimum_KLT_response_to_add)
break;
388 double min_dist_sqr = std::numeric_limits<double>::max();
390 if (!featureList.empty())
395 kdtree.kdTreeClosestPoint2DsqrError(feat.
pt.x, feat.
pt.y);
400 if (min_dist_sqr > threshold_sqr_dist_to_add_new)
403 featureList.push_back_fast(feat.
pt.x, feat.
pt.y);
404 kdtree.mark_as_outdated();
407 typename FEAT_LIST::feature_t& newFeat = featureList.back();
409 newFeat.ID = ++max_feat_ID_at_input;
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,
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);
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,
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);
449 template <
typename FEATLIST>
451 FEATLIST& trackedFeats,
const size_t img_width,
const size_t img_height,
452 const int MIN_DIST_MARGIN_TO_STOP_TRACKING);
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)
459 if (trackedFeats.empty())
return 0;
461 std::vector<size_t> survival_idxs;
462 const size_t N = trackedFeats.size();
465 survival_idxs.reserve(N);
466 for (
size_t i = 0; i < N; i++)
468 const typename FEATLIST::feature_t& ft = trackedFeats[i];
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))
486 if (!eras) survival_idxs.push_back(i);
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++)
494 if (survival_idxs[i] != i)
495 trackedFeats[i] = trackedFeats[survival_idxs[i]];
497 trackedFeats.resize(N2);
504 const size_t img_height,
const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
506 return trackFeatures_deleteOOB_impl_simple_feat<TSimpleFeatureList>(
507 trackedFeats, img_width, img_height, MIN_DIST_MARGIN_TO_STOP_TRACKING);
512 const size_t img_height,
const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
514 return trackFeatures_deleteOOB_impl_simple_feat<TSimpleFeaturefList>(
515 trackedFeats, img_width, img_height, MIN_DIST_MARGIN_TO_STOP_TRACKING);
520 CFeatureList& trackedFeats,
const size_t img_width,
const size_t img_height,
521 const int MIN_DIST_MARGIN_TO_STOP_TRACKING)
524 size_t n_removed = 0;
525 while (itFeat != trackedFeats.
end())
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))
544 itFeat = trackedFeats.
erase(itFeat);
578 template <
typename FEATLIST>
580 const CImage& old_img,
const CImage& new_img, FEATLIST& featureList)
583 "[CGenericFeatureTracker::trackFeatures] Complete iteration");
585 const size_t img_width = new_img.
getWidth();
586 const size_t img_height = new_img.
getHeight();
591 if (!featureList.empty()) max_feat_ID_at_input = featureList.getMaxID();
595 m_timlog.enter(
"[CGenericFeatureTracker] Convert grayscale");
600 m_timlog.leave(
"[CGenericFeatureTracker] Convert grayscale");
605 m_newly_detected_feats.clear();
607 m_timlog.enter(
"[CGenericFeatureTracker] trackFeatures_impl");
609 trackFeatures_impl(prev_gray, cur_gray, featureList);
611 m_timlog.leave(
"[CGenericFeatureTracker] trackFeatures_impl");
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);
623 if (check_KLT_response_every > 0 &&
624 ++m_check_KLT_counter >=
size_t(check_KLT_response_every))
626 m_timlog.enter(
"[CGenericFeatureTracker] check KLT responses");
627 m_check_KLT_counter = 0;
629 const unsigned int max_x = img_width - KLT_response_half_win;
630 const unsigned int max_y = img_height - KLT_response_half_win;
633 featureList, cur_gray, minimum_KLT_response, KLT_response_half_win,
636 m_timlog.leave(
"[CGenericFeatureTracker] check KLT responses");
644 const bool remove_lost_features =
645 extra_params.getWithDefaultVal(
"remove_lost_features", 0) != 0;
647 if (remove_lost_features)
649 m_timlog.enter(
"[CGenericFeatureTracker] removal of OOB");
651 static const int MIN_DIST_MARGIN_TO_STOP_TRACKING = 10;
654 featureList, img_width, img_height,
655 MIN_DIST_MARGIN_TO_STOP_TRACKING);
657 m_timlog.leave(
"[CGenericFeatureTracker] removal of OOB");
659 last_execution_extra_info.num_deleted_feats = nRemoved;
663 last_execution_extra_info.num_deleted_feats = 0;
669 const int update_patches_every =
670 extra_params.getWithDefaultVal(
"update_patches_every", 0);
672 if (update_patches_every > 0 &&
673 ++m_update_patches_counter >=
size_t(update_patches_every))
675 m_timlog.enter(
"[CGenericFeatureTracker] update patches");
676 m_update_patches_counter = 0;
681 m_timlog.leave(
"[CGenericFeatureTracker] update patches");
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);
695 if (add_new_features)
697 m_timlog.enter(
"[CGenericFeatureTracker] add new features");
701 if (m_newly_detected_feats.empty())
705 cur_gray, m_newly_detected_feats, m_detector_adaptive_thres);
708 const size_t N = m_newly_detected_feats.size();
710 last_execution_extra_info.raw_FAST_feats_detected =
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);
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++)
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 =
732 m_newly_detected_feats[i].response = 0;
739 std::vector<size_t> sorted_indices(N);
740 for (
size_t i = 0; i < N; i++) sorted_indices[i] = i;
743 sorted_indices.begin(), sorted_indices.end(),
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);
758 const float minimum_KLT_response_to_add =
759 extra_params.getWithDefaultVal(
"minimum_KLT_response_to_add", 10);
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);
768 m_timlog.leave(
"[CGenericFeatureTracker] add new features");
772 "[CGenericFeatureTracker::trackFeatures] Complete iteration");
779 internal_trackFeatures<CFeatureList>(old_img, new_img, featureList);
786 internal_trackFeatures<TSimpleFeatureList>(old_img, new_img, featureList);
793 internal_trackFeatures<TSimpleFeaturefList>(old_img, new_img, featureList);
797 const size_t nNewlyDetectedFeats,
const size_t desired_num_features)
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;
802 if (nNewlyDetectedFeats < hysteresis_min_num_feats)
803 m_detector_adaptive_thres = std::max(
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);
827 for (itLeft = leftList.
begin(), itRight = rightList.
begin();
828 itLeft != leftList.
end();)
830 bool delFeat =
false;
831 if ((*itLeft)->x < 0 || (*itLeft)->y < 0 ||
832 (*itRight)->x < 0 || (*itRight)->y < 0 ||
833 fabs((*itLeft)->y - (*itRight)->y) >
838 std::cout <<
"Bad tracked match:";
839 if ((*itLeft)->x < 0 || (*itLeft)->y < 0 || (*itRight)->x < 0 ||
841 std::cout <<
" Out of bounds: (" << (*itLeft)->x <<
"," 842 << (*itLeft)->y <<
" & (" << (*itRight)->x <<
"," 843 << (*itRight)->y <<
")" << std::endl;
845 if (fabs((*itLeft)->y - (*itRight)->y) > options.
epipolar_TH)
846 std::cout <<
" Bad row checking: " 847 << fabs((*itLeft)->y - (*itRight)->y) << std::endl;
855 (*itLeft)->patch, (*itRight)->patch, u,
v,
res);
859 std::cout <<
"Bad tracked match (correlation failed):" 860 <<
" CC Value: " <<
res << std::endl;
867 itLeft = leftList.
erase(itLeft);
868 itRight = rightList.
erase(itRight);
890 double v_mean, v_std;
891 unsigned int count = 0;
893 dist.setSize(feat_list.size(), 1);
898 for (itPair = feat_list.begin(); itPair != feat_list.end();
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));
913 dist.meanAndStdAll(v_mean, v_std);
916 <<
"*****************************************************" << endl;
917 cout <<
"Mean: " << v_mean <<
" - STD: " << v_std << endl;
919 <<
"*****************************************************" << endl;
922 unsigned int idx = 0;
924 for (itPair = feat_list.begin(); itPair != feat_list.end(); idx++)
927 if (fabs(dist(idx, 0) - v_mean) > v_std * numberOfSigmas)
929 cout <<
"Outlier deleted: " << dist(idx, 0) <<
" vs " 930 << v_std * numberOfSigmas << endl;
931 itPair = feat_list.erase(itPair);
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.
GLuint GLuint GLsizei count
Helper class: KD-tree search class for vector<KeyPoint>: Call mark_as_outdated() to force rebuilding ...
uint64_t TFeatureID
Definition of a feature ID.
Declares a matrix of booleans (non serializable).
void trackFeatures_updatePatch< TSimpleFeaturefList >(TSimpleFeaturefList &featureList, const CImage &cur_gray)
TInternalFeatList::iterator iterator
#define THROW_EXCEPTION(msg)
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)
TFeatureTrackStatus track_status
featKLT, featHarris, featSURF, featBeacon
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...
size_t getHeight() const override
Returns the height of the image in pixels.
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...
Feature correctly tracked.
float y
Coordinates in the image.
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_)
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.
FAST feature detector, OpenCV'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.
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
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)
void trackFeatures_updatePatch< TSimpleFeatureList >(TSimpleFeatureList &featureList, const CImage &cur_gray)
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...
A pair (x,y) of pixel coordinates (integer resolution).
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)
Classes for computer vision, detectors, features, etc.
A generic 2D feature from an image, extracted with CFeatureExtraction Each feature may have one or mo...
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...
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)
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.
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 ...
float response
process (old name: KLT_status)
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)
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)
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...
void filterBadCorrsByDistance(mrpt::tfest::TMatchingPairList &list, unsigned int numberOfSigmas)
Filter bad correspondences by distance ...
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)
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)
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)
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)
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".
mrpt::img::CImage patch
A patch of the image surrounding the feature.
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)
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)
A class for storing images as grayscale or RGB bitmaps.
void fillAll(const T &val)
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
int round(const T value)
Returns the closer integer (int) to x.