MRPT  2.0.2
vision/include/mrpt/vision/types.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
12 #include <mrpt/img/CImage.h>
13 #include <mrpt/math/TPoint3D.h>
16 #include <map>
17 #include <vector>
18 
19 namespace mrpt::vision
20 {
21 /** \addtogroup mrpt_vision_grp
22  * @{ */
23 /** Definition of a feature ID */
24 using TFeatureID = uint64_t;
25 
26 /** Unique IDs for landmarks */
27 using TLandmarkID = uint64_t;
28 /** Unique IDs for camera frames (poses) */
29 using TCameraPoseID = uint64_t;
30 
31 /** A list of camera frames (6D poses) indexed by unique IDs. */
32 using TFramePosesMap = std::map<TCameraPoseID, mrpt::poses::CPose3D>;
33 /** A list of camera frames (6D poses), which assumes indexes are unique,
34  * consecutive IDs. */
35 using TFramePosesVec = std::vector<mrpt::poses::CPose3D>;
36 
37 /** A list of landmarks (3D points) indexed by unique IDs. */
38 using TLandmarkLocationsMap = std::map<TLandmarkID, mrpt::math::TPoint3D>;
39 /** A list of landmarks (3D points), which assumes indexes are unique,
40  * consecutive IDs. */
41 using TLandmarkLocationsVec = std::vector<mrpt::math::TPoint3D>;
42 
43 /** Types of key point detectors */
44 enum TKeyPointMethod : int8_t
45 {
46  /** Non-defined feature (also used for Occupancy features) */
48  /** Kanade-Lucas-Tomasi feature [SHI'94] */
49  featKLT = 0,
50  /** Harris border and corner detector [HARRIS] */
52  /* featBCD = 2, ==> deprecated in MRPT 2.0 */
53  /** Scale Invariant Feature Transform [LOWE'04] */
54  featSIFT = 3,
55  /** Speeded Up Robust Feature [BAY'06] */
56  featSURF = 4,
57  /** A especial case: this is not an image feature, but a 2D/3D beacon (used
58  for range-only SLAM from mrpt::maps::CLandmark) */
60  /** FAST feature detector, OpenCV's implementation ("Faster and better: A
61  machine learning approach to corner detection", E. Rosten, R. Porter and
62  T. Drummond, PAMI, 2009). */
63  featFAST = 6,
64  /** ORB detector and descriptor, OpenCV's implementation */
65  featORB = 10,
66  // #added by Raghavender Sahdev
67  featAKAZE = 11, //!< AKAZE detector, OpenCV's implementation
68  featLSD = 12 //!< LSD detector, OpenCV's implementation
69  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
70 };
71 
72 /** The bitwise OR combination of values of TDescriptorType are used in
73  * CFeatureExtraction::computeDescriptors to indicate which descriptors are to
74  * be computed for features.
75  */
76 enum TDescriptorType : uint16_t
77 {
78  /** Used in some methods to mean "any of the present descriptors" */
79  descAny = 0,
80  /** SIFT descriptors */
81  descSIFT = 1,
82  /** SURF descriptors */
83  descSURF = 2,
84  /** Intensity-domain spin image descriptors */
86  /** Polar image descriptor */
88  /** Log-Polar image descriptor */
90  /** Bit-based feature descriptor */
91  descORB = 32,
92  descBLD = 64, //!< BLD Line descriptor
93  descLATCH = 128 //!< LATCH Line descriptor
94  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
95 };
96 
97 enum TFeatureTrackStatus : uint8_t
98 {
99  // Init value
100  /** Inactive (right after detection, and before being tried to track) */
102 
103  // Ok:
104  /** Feature correctly tracked */
106 
107  // Bad:
108  /** Feature fell Out Of Bounds (out of the image limits, too close to image
109  borders) */
111  /** Unable to track this feature (mismatch is too high for the given
112  tracking window: lack of texture? oclussion?) */
114 };
115 
116 /** One feature observation entry, used within sequences with
117  * TSequenceFeatureObservations */
119 {
120  inline TFeatureObservation() = default;
122  const TLandmarkID _id_feature, const TCameraPoseID _id_frame,
123  const mrpt::img::TPixelCoordf& _px)
124  : id_feature(_id_feature), id_frame(_id_frame), px(_px)
125  {
126  }
127 
128  /** A unique ID of this feature */
130  /** A unique ID of a "frame" (camera position) from where the feature was
131  * observed. */
133  /** The pixel coordinates of the observed feature */
135 };
136 
137 /** One relative feature observation entry, used with some relative
138  * bundle-adjustment functions.
139  */
141 {
142  inline TRelativeFeaturePos() = default;
144  const mrpt::vision::TCameraPoseID _id_frame_base,
145  const mrpt::math::TPoint3D& _pos)
146  : id_frame_base(_id_frame_base), pos(_pos)
147  {
148  }
149 
150  /** The ID of the camera frame which is the coordinate reference of \a pos
151  */
153  /** The (x,y,z) location of the feature, wrt to the camera frame \a
154  * id_frame_base */
156 };
157 
158 /** An index of feature IDs and their relative locations */
160  std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos>;
161 
162 /** A complete sequence of observations of features from different camera frames
163  * (poses).
164  * This structure is the input to some (Bundle-adjustment) methods in
165  * mrpt::vision
166  * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc
167  * of functions handling this structure to see what they expect.
168  * \sa mrpt::vision::bundle_adj_full
169  */
170 struct TSequenceFeatureObservations : public std::vector<TFeatureObservation>
171 {
172  using BASE = std::vector<TFeatureObservation>;
173 
174  inline TSequenceFeatureObservations() = default;
177 
178  = default;
179 
180  /** Saves all entries to a text file, with each line having this format:
181  * #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y
182  * The file is self-descripting, since the first line contains a comment
183  * line (starting with '%') explaining the format.
184  * Generated files can be loaded from MATLAB.
185  * \sa loadFromTextFile \exception std::exception On I/O error */
186  void saveToTextFile(
187  const std::string& filName, bool skipFirstCommentLine = false) const;
188 
189  /** Load from a text file, in the format described in \a saveToTextFile
190  * \exception std::exception On I/O or format error */
191  void loadFromTextFile(const std::string& filName);
192 
193  /** Save the list of observations + the point locations + the camera frame
194  * poses to a pair of files in the format
195  * used by the Sparse Bundle Adjustment (SBA) C++ library.
196  *
197  * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
198  *
199  * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)
200  * \return false on any error
201  */
202  bool saveAsSBAFiles(
203  const TLandmarkLocationsVec& pts, const std::string& pts_file,
204  const TFramePosesVec& cams, const std::string& cams_file) const;
205 
206  /** Remove all those features that don't have a minimum number of
207  * observations from different camera frame IDs.
208  * \return the number of erased entries.
209  * \sa After calling this you may want to call \a compressIDs */
210  size_t removeFewObservedFeatures(size_t minNumObservations = 3);
211 
212  /** Remove all but one out of \a decimate_ratio camera frame IDs from the
213  * list (eg: from N camera pose IDs at return there will be just
214  * N/decimate_ratio)
215  * The algorithm first builds a sorted list of frame IDs, then keep the
216  * lowest ID, remove the next "decimate_ratio-1", and so on.
217  * \sa After calling this you may want to call \a compressIDs */
218  void decimateCameraFrames(const size_t decimate_ratio);
219 
220  /** Rearrange frame and feature IDs such as they start at 0 and there are no
221  * gaps.
222  * \param old2new_camIDs If provided, the mapping from old to new IDs is
223  * stored here.
224  * \param old2new_lmIDs If provided, the mapping from old to new IDs is
225  * stored here. */
226  void compressIDs(
227  std::map<TCameraPoseID, TCameraPoseID>* old2new_camIDs = nullptr,
228  std::map<TLandmarkID, TLandmarkID>* old2new_lmIDs = nullptr);
229 };
230 
231 /** Parameters associated to a stereo system
232  */
234 {
235  /** Initilization of default parameters */
237 
238  void loadFromConfigFile(
239  const mrpt::config::CConfigFileBase& source,
240  const std::string& section) override; // See base docs
241  void dumpToTextStream(std::ostream& out) const override; // See base docs
242 
243  /** Method for propagating the feature's image coordinate uncertainty into
244  * 3D space. Default value: Prop_Linear
245  */
247  {
248  /** Linear propagation of the uncertainty
249  */
251  /** Uncertainty propagation through the Unscented Transformation
252  */
254  /** Uncertainty propagation through the Scaled Unscented Transformation
255  */
257  };
258 
260 
261  /** Stereo Fundamental matrix */
263 
264  /** Intrinsic parameters
265  */
267  /** Baseline. Default value: baseline = 0.119f; [Bumblebee]
268  */
269  float baseline{0.119f};
270  /** Standard deviation of the error in feature detection. Default value:
271  * stdPixel = 1
272  */
273  float stdPixel{1};
274  /** Standard deviation of the error in disparity computation. Default value:
275  * stdDisp = 1
276  */
277  float stdDisp{1};
278  /** Maximum allowed distance. Default value: maxZ = 20.0f
279  */
280  float maxZ{20.0f};
281  /** Maximum allowed distance. Default value: minZ = 0.5f
282  */
283  float minZ{0.5f};
284  /** Maximum allowed height. Default value: maxY = 3.0f
285  */
286  float maxY{3.0f};
287  /** K factor for the UT. Default value: k = 1.5f
288  */
289  float factor_k{1.5f};
290  /** Alpha factor for SUT. Default value: a = 1e-3
291  */
292  float factor_a{1e-3f};
293  /** Beta factor for the SUT. Default value: b = 2.0f
294  */
295  float factor_b{2.0f};
296 
297  /** Parameters initialization
298  */
299  // TStereoSystemParams();
300 
301 }; // End struct TStereoSystemParams
302 
303 /** A structure for storing a 3D ROI
304  */
305 struct TROI
306 {
307  // Constructors
308  TROI() = default;
309  TROI(float x1, float x2, float y1, float y2, float z1, float z2)
310  : xMin(x1), xMax(x2), yMin(y1), yMax(y2), zMin(z1), zMax(z2)
311  {
312  }
313 
314  // Members
315  float xMin{0};
316  float xMax{0};
317  float yMin{0};
318  float yMax{0};
319  float zMin{0};
320  float zMax{0};
321 }; // end struct TROI
322 
323 /** A structure for defining a ROI within an image
324  */
325 struct TImageROI
326 {
327  // Constructors
328  TImageROI() = default;
329  TImageROI(size_t x1, size_t x2, size_t y1, size_t y2)
330  : xMin(x1), xMax(x2), yMin(y1), yMax(y2)
331  {
332  }
333 
334  /** X coordinate limits [0,imageWidth) */
335  size_t xMin{0}, xMax{0};
336  /** Y coordinate limits [0,imageHeight) */
337  size_t yMin{0}, yMax{0};
338 };
339 
340 /** A structure containing options for the matching
341  */
343 {
344  /** Method for propagating the feature's image coordinate uncertainty into
345  * 3D space. Default value: Prop_Linear
346  */
348  {
349  /** Matching by cross correlation of the image patches
350  */
352  /** Matching by Euclidean distance between SIFT descriptors
353  */
355  /** Matching by Euclidean distance between SURF descriptors
356  */
358  /** Matching by sum of absolute differences of the image patches
359  */
361  /** Matching by Hamming distance between ORB descriptors
362  */
364  };
365 
366  // For determining
367  /** Whether or not take into account the epipolar restriction for finding
368  * correspondences */
370  /** Whether or not there is a fundamental matrix */
371  bool hasFundamentalMatrix{false};
372  /** Whether or not the stereo rig has the optical axes parallel */
374  /** Whether or not employ the x-coord restriction for finding
375  * correspondences (bumblebee camera, for example) */
376  bool useXRestriction{true};
377  /** Whether or not to add the matches found into the input matched list (if
378  * false the input list will be cleared before being filled with the new
379  * matches) */
380  bool addMatches{false};
381  /** Whether or not use limits (min,max) for the disparity, see also
382  * 'min_disp, max_disp' */
383  bool useDisparityLimits{false};
384  /** Whether or not only permit matches that are consistent from left->right
385  * and right->left */
387 
388  /** Disparity limits, see also 'useDisparityLimits' */
389  float min_disp{1.0f}, max_disp{1e4f};
390 
392 
393  // General
394  /** Matching method */
396  /** Epipolar constraint (rows of pixels) */
397  float epipolar_TH{1.5f};
398 
399  // SIFT
400  /** Maximum Euclidean Distance Between SIFT Descriptors */
401  float maxEDD_TH{90.0f};
402  /** Boundary Ratio between the two lowest EDD */
403  float EDD_RATIO{0.6f};
404 
405  // KLT
406  /** Minimum Value of the Cross Correlation */
407  float minCC_TH{0.95f};
408  /** Minimum Difference Between the Maximum Cross Correlation Values */
409  float minDCC_TH{0.025f};
410  /** Maximum Ratio Between the two highest CC values */
411  float rCC_TH{0.92f};
412 
413  // SURF
414  /** Maximum Euclidean Distance Between SURF Descriptors */
415  float maxEDSD_TH{0.15f};
416  /** Boundary Ratio between the two lowest SURF EDSD */
417  float EDSD_RATIO{0.6f};
418 
419  // SAD
420  /** Minimum Euclidean Distance Between Sum of Absolute Differences */
421  double maxSAD_TH{0.4};
422  /** Boundary Ratio between the two highest SAD */
423  double SAD_RATIO{0.5};
424 
425  // ORB
426  /** Maximun distance between ORB descriptors */
427  double maxORB_dist;
428 
429  // // To estimate depth
430  /** Whether or not estimate the 3D position of the real features for the
431  * matches (only with parallelOpticalAxis by now). */
432  bool estimateDepth{false};
433  /** The maximum allowed depth for the matching. If its computed depth is
434  * larger than this, the match won't be considered. */
435  double maxDepthThreshold{15.0};
436  /** Intrinsic parameters of the stereo rig */
437  // double fx,cx,cy,baseline;
438 
439  /** Constructor */
441 
442  void loadFromConfigFile(
443  const mrpt::config::CConfigFileBase& source,
444  const std::string& section) override; // See base docs
445  void dumpToTextStream(std::ostream& out) const override; // See base docs
446 
447 #define COPY_MEMBER(_m) this->_m = o._m;
448 #define CHECK_MEMBER(_m) this->_m == o._m
449 
450  bool operator==(const TMatchingOptions& o) const
451  {
452  return CHECK_MEMBER(useXRestriction) &&
467  }
468 
470  {
480  COPY_MEMBER(F)
495  }
496 
497 }; // end struct TMatchingOptions
498 
499 /** Struct containing the output after matching multi-resolution SIFT-like
500  * descriptors
501  */
503 {
504  int nMatches{0};
505 
506  /** Contains the indexes within the second list corresponding to the first
507  * one. */
508  std::vector<int> firstListCorrespondences;
509  /** Contains the indexes within the first list corresponding to the second
510  * one. */
511  std::vector<int> secondListCorrespondences;
512  /** Contains the scales of the first list where the correspondence was
513  * found. */
514  std::vector<int> firstListFoundScales;
515  /** Contains the distances between the descriptors. */
516  std::vector<double> firstListDistance;
517 
518  TMultiResMatchingOutput() = default;
519 
520 }; // end struct TMultiResMatchingOutput
521 
522 /** Struct containing the options when matching multi-resolution SIFT-like
523  * descriptors
524  */
526 {
527  /** Whether or not use the filter based on orientation test */
528  bool useOriFilter{true};
529  /** The threshold for the orientation test */
530  double oriThreshold{0.2};
531 
532  /** Whether or not use the filter based on the depth test */
533  bool useDepthFilter{true};
534 
535  /** The absolute threshold in descriptor distance for considering a match */
536  double matchingThreshold{1e4};
537  /** The ratio between the two lowest distances threshold for considering a
538  * match */
540  /** The lowest scales in the two features to be taken into account in the
541  * matching process */
542  uint32_t lowScl1{0}, lowScl2{0};
543  /** The highest scales in the two features to be taken into account in the
544  * matching process */
545  uint32_t highScl1{6}, highScl2{6};
546 
547  /** Size of the squared area where to search for a match. */
548  uint32_t searchAreaSize{20};
549  /** The allowed number of frames since a certain feature was seen for the
550  * last time. */
551  uint32_t lastSeenThreshold{10};
552  /** The minimum number of frames for a certain feature to be considered
553  * stable. */
554  uint32_t timesSeenThreshold{5};
555 
556  /** The minimum number of features allowed in the system. If current number
557  * is below this value, more features will be found. */
558  uint32_t minFeaturesToFind{30};
559  /** The minimum number of features allowed in the system to not be
560  * considered to be lost. */
561  uint32_t minFeaturesToBeLost{5};
562 
563  /** Default constructor
564  */
565  TMultiResDescMatchOptions() = default;
566 
568  bool _useOriFilter, double _oriThreshold, bool _useDepthFilter,
569  double _th, double _th2, const unsigned int& _lwscl1,
570  const unsigned int& _lwscl2, const unsigned int& _hwscl1,
571  const unsigned int& _hwscl2, int _searchAreaSize, int _lsth, int _tsth,
572  int _minFeaturesToFind, int _minFeaturesToBeLost)
573  : useOriFilter(_useOriFilter),
574  oriThreshold(_oriThreshold),
575  useDepthFilter(_useDepthFilter),
576  matchingThreshold(_th),
578  lowScl1(_lwscl1),
579  lowScl2(_lwscl2),
580  highScl1(_hwscl1),
581  highScl2(_hwscl2),
582  searchAreaSize(_searchAreaSize),
583  lastSeenThreshold(_lsth),
584  timesSeenThreshold(_tsth),
585  minFeaturesToFind(_minFeaturesToFind),
586  minFeaturesToBeLost(_minFeaturesToBeLost)
587  {
588  }
589 
590  void loadFromConfigFile(
592  const std::string& section) override;
593  void saveToConfigFile(
595  const std::string& section) const override;
596  void dumpToTextStream(std::ostream& out) const override;
597 
598 }; // end TMultiResDescMatchOptions
599 
600 /** Struct containing the options when computing the multi-resolution SIFT-like
601  * descriptors
602  */
604 {
605  /** The size of the base patch */
606  uint32_t basePSize{23};
607  /** The set of scales relatives to the base patch */
608  std::vector<double> scales;
609  /** The subset of scales for which to compute the descriptors */
610  uint32_t comLScl, comHScl;
611  /** The sigmas for the Gaussian kernels */
612  double sg1{0.5}, sg2{7.5}, sg3{8.0};
613  /** Whether or not to compute the depth of the feature */
614  bool computeDepth{true};
615  /** Whether or not to blur the image previously to compute the descriptors
616  */
617  bool blurImage{true};
618  /** Intrinsic stereo pair parameters for computing the depth of the feature
619  */
620  double fx{0.0}, cx{0.0}, cy{0.0}, baseline{0.0};
621  /** Whether or not compute the coefficients for mantaining a HASH table of
622  * descriptors (for relocalization) */
623  bool computeHashCoeffs{false};
624 
625  /** The SIFT-like descriptor is cropped at this value during normalization
626  */
627  double cropValue{0.2};
628 
629  /** Default constructor
630  */
632  {
633  scales.resize(7);
634  scales[0] = 0.5;
635  scales[1] = 0.8;
636  scales[2] = 1.0;
637  scales[3] = 1.2;
638  scales[4] = 1.5;
639  scales[5] = 1.8;
640  scales[6] = 2.0;
641  comLScl = 0;
642  comHScl = 6;
643  }
644 
646  const unsigned int& _basePSize, const std::vector<double>& _scales,
647  const unsigned int& _comLScl, const unsigned int& _comHScl, double _sg1,
648  double _sg2, double _sg3, bool _computeDepth, const bool _blurImage,
649  double _fx, double _cx, double _cy, double _baseline,
650  bool _computeHashCoeffs, double _cropValue)
651  : basePSize(_basePSize),
652  comLScl(_comLScl),
653  comHScl(_comHScl),
654  sg1(_sg1),
655  sg2(_sg2),
656  sg3(_sg3),
657  computeDepth(_computeDepth),
658  blurImage(_blurImage),
659  fx(_fx),
660  cx(_cx),
661  cy(_cy),
662  baseline(_baseline),
663  computeHashCoeffs(_computeHashCoeffs),
664  cropValue(_cropValue)
665  {
666  scales.resize(_scales.size());
667  for (unsigned int k = 0; k < _scales.size(); ++k)
668  scales[k] = _scales[k];
669  }
670 
671  void loadFromConfigFile(
672  const mrpt::config::CConfigFileBase& source,
673  const std::string& section) override; // See base docs
674  void saveToConfigFile(
676  const std::string& section) const override; // See base docs
677  void dumpToTextStream(std::ostream& out) const override; // See base docs
678 
679 }; // end TMultiResDescOptions
680 
681 /** @} */ // end of grouping
682 } // namespace mrpt::vision
684 using namespace mrpt::vision;
696 
698 using namespace mrpt::vision;
TUnc_Prop_Method
Method for propagating the feature&#39;s image coordinate uncertainty into 3D space.
float EDD_RATIO
Boundary Ratio between the two lowest EDD.
TMatchingOptions()
Intrinsic parameters of the stereo rig.
void loadFromTextFile(const std::string &filName)
Load from a text file, in the format described in saveToTextFile.
Definition: types.cpp:52
float rCC_TH
Maximum Ratio Between the two highest CC values.
TLandmarkID id_feature
A unique ID of this feature.
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
mrpt::math::CMatrixDouble33 F
Stereo Fundamental matrix.
uint32_t minFeaturesToFind
The minimum number of features allowed in the system.
uint64_t TFeatureID
Definition of a feature ID.
void operator=(const TMatchingOptions &o)
double maxORB_dist
Maximun distance between ORB descriptors.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
bool estimateDepth
Whether or not estimate the 3D position of the real features for the matches (only with parallelOptic...
uint64_t TLandmarkID
Unique IDs for landmarks.
Non-defined feature (also used for Occupancy features)
bool useXRestriction
Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera...
size_t size(const MATRIXLIKE &m, const int dim)
TMultiResDescMatchOptions(bool _useOriFilter, double _oriThreshold, bool _useDepthFilter, double _th, double _th2, const unsigned int &_lwscl1, const unsigned int &_lwscl2, const unsigned int &_hwscl1, const unsigned int &_hwscl2, int _searchAreaSize, int _lsth, int _tsth, int _minFeaturesToFind, int _minFeaturesToBeLost)
double SAD_RATIO
Boundary Ratio between the two highest SAD.
Intensity-domain spin image descriptors.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Unable to track this feature (mismatch is too high for the given tracking window: lack of texture...
float min_disp
Disparity limits, see also &#39;useDisparityLimits&#39;.
Bit-based feature descriptor.
Struct containing the output after matching multi-resolution SIFT-like descriptors.
One feature observation entry, used within sequences with TSequenceFeatureObservations.
Scale Invariant Feature Transform [LOWE&#39;04].
#define CHECK_MEMBER(_m)
A pair (x,y) of pixel coordinates (subpixel resolution).
Definition: TPixelCoord.h:18
std::vector< int > secondListCorrespondences
Contains the indexes within the first list corresponding to the second one.
float epipolar_TH
Epipolar constraint (rows of pixels)
A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt...
uint32_t highScl1
The highest scales in the two features to be taken into account in the matching process.
float EDSD_RATIO
Boundary Ratio between the two lowest SURF EDSD.
bool useEpipolarRestriction
Whether or not take into account the epipolar restriction for finding correspondences.
std::vector< double > firstListDistance
Contains the distances between the descriptors.
Matching by Hamming distance between ORB descriptors.
void saveToConfigFile(mrpt::config::CConfigFileBase &cfg, const std::string &section) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
Definition: CFeature.cpp:70
LSD detector, OpenCV&#39;s implementation.
MRPT_FILL_ENUM(featNotDefined)
Used in some methods to mean "any of the present descriptors".
A complete sequence of observations of features from different camera frames (poses).
A structure for storing a 3D ROI.
bool useDisparityLimits
Whether or not use limits (min,max) for the disparity, see also &#39;min_disp, max_disp&#39;.
float stdPixel
Standard deviation of the error in feature detection.
A structure for defining a ROI within an image.
bool computeHashCoeffs
Whether or not compute the coefficients for mantaining a HASH table of descriptors (for relocalizatio...
size_t yMin
Y coordinate limits [0,imageHeight)
uint32_t comLScl
The subset of scales for which to compute the descriptors.
std::vector< int > firstListFoundScales
Contains the scales of the first list where the correspondence was found.
Matching by Euclidean distance between SIFT descriptors.
std::vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
bool parallelOpticalAxis
Whether or not the stereo rig has the optical axes parallel.
float minDCC_TH
Minimum Difference Between the Maximum Cross Correlation Values.
Inactive (right after detection, and before being tried to track)
This class allows loading and storing values and vectors of different types from a configuration text...
uint32_t basePSize
The size of the base patch.
double sg1
The sigmas for the Gaussian kernels.
uint32_t timesSeenThreshold
The minimum number of frames for a certain feature to be considered stable.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
TMatchingMethod
Method for propagating the feature&#39;s image coordinate uncertainty into 3D space.
TMultiResDescMatchOptions()=default
Default constructor.
Parameters associated to a stereo system.
bool addMatches
Whether or not to add the matches found into the input matched list (if false the input list will be ...
uint32_t lastSeenThreshold
The allowed number of frames since a certain feature was seen for the last time.
bool useDepthFilter
Whether or not use the filter based on the depth test.
Matching by Euclidean distance between SURF descriptors.
std::map< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
Feature fell Out Of Bounds (out of the image limits, too close to image borders)
TKeyPointMethod
Types of key point detectors.
TDescriptorType
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...
TROI(float x1, float x2, float y1, float y2, float z1, float z2)
Classes for computer vision, detectors, features, etc.
Definition: CDifodo.h:17
Uncertainty propagation through the Unscented Transformation.
void saveToTextFile(const std::string &filName, bool skipFirstCommentLine=false) const
Saves all entries to a text file, with each line having this format: #FRAME_ID #FEAT_ID #PIXEL_X #PIX...
Definition: types.cpp:31
std::vector< int > firstListCorrespondences
Contains the indexes within the second list corresponding to the first one.
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
double maxDepthThreshold
The maximum allowed depth for the matching.
bool saveAsSBAFiles(const TLandmarkLocationsVec &pts, const std::string &pts_file, const TFramePosesVec &cams, const std::string &cams_file) const
Save the list of observations + the point locations + the camera frame poses to a pair of files in th...
Definition: types.cpp:89
Speeded Up Robust Feature [BAY&#39;06].
One relative feature observation entry, used with some relative bundle-adjustment functions...
double cropValue
The SIFT-like descriptor is cropped at this value during normalization.
FAST feature detector, OpenCV&#39;s implementation ("Faster and better: A machine learning approach to...
std::map< mrpt::vision::TFeatureID, TRelativeFeaturePos > TRelativeFeaturePosMap
An index of feature IDs and their relative locations.
mrpt::img::TPixelCoordf px
The pixel coordinates of the observed feature.
TStereoSystemParams()
Initilization of default parameters.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CFeature.cpp:213
Matching by sum of absolute differences of the image patches.
uint32_t searchAreaSize
Size of the squared area where to search for a match.
double maxSAD_TH
Minimum Euclidean Distance Between Sum of Absolute Differences.
size_t xMin
X coordinate limits [0,imageWidth)
std::vector< double > scales
The set of scales relatives to the base patch.
AKAZE detector, OpenCV&#39;s implementation.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void saveToConfigFile(mrpt::config::CConfigFileBase &cfg, const std::string &section) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
Definition: CFeature.cpp:185
bool computeDepth
Whether or not to compute the depth of the feature.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
double oriThreshold
The threshold for the orientation test.
Harris border and corner detector [HARRIS].
#define COPY_MEMBER(_m)
uint32_t lowScl1
The lowest scales in the two features to be taken into account in the matching process.
Struct containing the options when computing the multi-resolution SIFT-like descriptors.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CFeature.cpp:103
TRelativeFeaturePos(const mrpt::vision::TCameraPoseID _id_frame_base, const mrpt::math::TPoint3D &_pos)
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
Load all the params from a config source, in the format described in saveToConfigFile() ...
Definition: CFeature.cpp:150
mrpt::vision::TStereoCalibResults out
bool enable_robust_1to1_match
Whether or not only permit matches that are consistent from left->right and right->left.
std::map< TCameraPoseID, mrpt::poses::CPose3D > TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
A structure containing options for the matching.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &cfg, const std::string &section) override
Load all the params from a config source, in the format described in saveToConfigFile() ...
Definition: CFeature.cpp:41
Matching by cross correlation of the image patches.
bool hasFundamentalMatrix
Whether or not there is a fundamental matrix.
Kanade-Lucas-Tomasi feature [SHI&#39;94].
size_t removeFewObservedFeatures(size_t minNumObservations=3)
Remove all those features that don&#39;t have a minimum number of observations from different camera fram...
Definition: types.cpp:136
Struct containing the options when matching multi-resolution SIFT-like descriptors.
float maxEDSD_TH
Maximum Euclidean Distance Between SURF Descriptors.
float minCC_TH
Minimum Value of the Cross Correlation.
mrpt::vision::TCameraPoseID id_frame_base
The ID of the camera frame which is the coordinate reference of pos.
TCameraPoseID id_frame
A unique ID of a "frame" (camera position) from where the feature was observed.
double matchingThreshold
The absolute threshold in descriptor distance for considering a match.
float maxEDD_TH
Maximum Euclidean Distance Between SIFT Descriptors.
TFeatureObservation(const TLandmarkID _id_feature, const TCameraPoseID _id_frame, const mrpt::img::TPixelCoordf &_px)
bool operator==(const TMatchingOptions &o) const
uint32_t minFeaturesToBeLost
The minimum number of features allowed in the system to not be considered to be lost.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
TMatchingMethod matching_method
Matching method.
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
mrpt::math::TPoint3D pos
The (x,y,z) location of the feature, wrt to the camera frame id_frame_base.
bool useOriFilter
Whether or not use the filter based on orientation test.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
bool blurImage
Whether or not to blur the image previously to compute the descriptors.
double fx
Intrinsic stereo pair parameters for computing the depth of the feature.
double matchingRatioThreshold
The ratio between the two lowest distances threshold for considering a match.
void compressIDs(std::map< TCameraPoseID, TCameraPoseID > *old2new_camIDs=nullptr, std::map< TLandmarkID, TLandmarkID > *old2new_lmIDs=nullptr)
Rearrange frame and feature IDs such as they start at 0 and there are no gaps.
Definition: types.cpp:198
ORB detector and descriptor, OpenCV&#39;s implementation.
Uncertainty propagation through the Scaled Unscented Transformation.
void decimateCameraFrames(const size_t decimate_ratio)
Remove all but one out of decimate_ratio camera frame IDs from the list (eg: from N camera pose IDs a...
Definition: types.cpp:164
float stdDisp
Standard deviation of the error in disparity computation.
TImageROI(size_t x1, size_t x2, size_t y1, size_t y2)
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.
TMultiResDescOptions(const unsigned int &_basePSize, const std::vector< double > &_scales, const unsigned int &_comLScl, const unsigned int &_comHScl, double _sg1, double _sg2, double _sg3, bool _computeDepth, const bool _blurImage, double _fx, double _cx, double _cy, double _baseline, bool _computeHashCoeffs, double _cropValue)



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020