MRPT  1.9.9
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-2019, 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 */
25 
26 /** Unique IDs for landmarks */
28 /** Unique IDs for camera frames (poses) */
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 */
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] */
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). */
64  /** FASTER-9 detector, Edward Rosten's libcvd, SSE2 optimized */
66  /** FASTER-9 detector, Edward Rosten's libcvd, SSE2 optimized */
68  /** FASTER-9 detector, Edward Rosten's libcvd, SSE2 optimized */
70  /** ORB detector and descriptor, OpenCV's implementation */
72  // #added by Raghavender Sahdev
73  featAKAZE, //!< AKAZE detector, OpenCV's implementation
74  featLSD //!< LSD detector, OpenCV's implementation
75  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
76 };
77 
78 /** The bitwise OR combination of values of TDescriptorType are used in
79  * CFeatureExtraction::computeDescriptors to indicate which descriptors are to
80  * be computed for features.
81  */
83 {
84  /** Used in some methods to mean "any of the present descriptors" */
85  descAny = 0,
86  /** SIFT descriptors */
87  descSIFT = 1,
88  /** SURF descriptors */
89  descSURF = 2,
90  /** Intensity-domain spin image descriptors */
92  /** Polar image descriptor */
94  /** Log-Polar image descriptor */
96  /** Bit-based feature descriptor */
97  descORB = 32,
98  descBLD = 64, //!< BLD Line descriptor
99  descLATCH = 128 //!< LATCH Line descriptor
100  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
101 };
102 
104 {
105  // Init value
106  /** Inactive (right after detection, and before being tried to track) */
108 
109  // Ok:
110  /** Feature correctly tracked */
112 
113  // Bad:
114  /** Feature fell Out Of Bounds (out of the image limits, too close to image
115  borders) */
117  /** Unable to track this feature (mismatch is too high for the given
118  tracking window: lack of texture? oclussion?) */
120 };
121 
122 /** One feature observation entry, used within sequences with
123  * TSequenceFeatureObservations */
125 {
126  inline TFeatureObservation() = default;
128  const TLandmarkID _id_feature, const TCameraPoseID _id_frame,
129  const mrpt::img::TPixelCoordf& _px)
130  : id_feature(_id_feature), id_frame(_id_frame), px(_px)
131  {
132  }
133 
134  /** A unique ID of this feature */
136  /** A unique ID of a "frame" (camera position) from where the feature was
137  * observed. */
139  /** The pixel coordinates of the observed feature */
141 };
142 
143 /** One relative feature observation entry, used with some relative
144  * bundle-adjustment functions.
145  */
147 {
148  inline TRelativeFeaturePos() = default;
150  const mrpt::vision::TCameraPoseID _id_frame_base,
151  const mrpt::math::TPoint3D& _pos)
152  : id_frame_base(_id_frame_base), pos(_pos)
153  {
154  }
155 
156  /** The ID of the camera frame which is the coordinate reference of \a pos
157  */
159  /** The (x,y,z) location of the feature, wrt to the camera frame \a
160  * id_frame_base */
162 };
163 
164 /** An index of feature IDs and their relative locations */
166  std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos>;
167 
168 /** A complete sequence of observations of features from different camera frames
169  * (poses).
170  * This structure is the input to some (Bundle-adjustment) methods in
171  * mrpt::vision
172  * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc
173  * of functions handling this structure to see what they expect.
174  * \sa mrpt::vision::bundle_adj_full
175  */
176 struct TSequenceFeatureObservations : public std::vector<TFeatureObservation>
177 {
178  using BASE = std::vector<TFeatureObservation>;
179 
180  inline TSequenceFeatureObservations() = default;
183 
184  = default;
185 
186  /** Saves all entries to a text file, with each line having this format:
187  * #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y
188  * The file is self-descripting, since the first line contains a comment
189  * line (starting with '%') explaining the format.
190  * Generated files can be loaded from MATLAB.
191  * \sa loadFromTextFile \exception std::exception On I/O error */
192  void saveToTextFile(
193  const std::string& filName, bool skipFirstCommentLine = false) const;
194 
195  /** Load from a text file, in the format described in \a saveToTextFile
196  * \exception std::exception On I/O or format error */
197  void loadFromTextFile(const std::string& filName);
198 
199  /** Save the list of observations + the point locations + the camera frame
200  * poses to a pair of files in the format
201  * used by the Sparse Bundle Adjustment (SBA) C++ library.
202  *
203  * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
204  *
205  * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)
206  * \return false on any error
207  */
208  bool saveAsSBAFiles(
209  const TLandmarkLocationsVec& pts, const std::string& pts_file,
210  const TFramePosesVec& cams, const std::string& cams_file) const;
211 
212  /** Remove all those features that don't have a minimum number of
213  * observations from different camera frame IDs.
214  * \return the number of erased entries.
215  * \sa After calling this you may want to call \a compressIDs */
216  size_t removeFewObservedFeatures(size_t minNumObservations = 3);
217 
218  /** Remove all but one out of \a decimate_ratio camera frame IDs from the
219  * list (eg: from N camera pose IDs at return there will be just
220  * N/decimate_ratio)
221  * The algorithm first builds a sorted list of frame IDs, then keep the
222  * lowest ID, remove the next "decimate_ratio-1", and so on.
223  * \sa After calling this you may want to call \a compressIDs */
224  void decimateCameraFrames(const size_t decimate_ratio);
225 
226  /** Rearrange frame and feature IDs such as they start at 0 and there are no
227  * gaps.
228  * \param old2new_camIDs If provided, the mapping from old to new IDs is
229  * stored here.
230  * \param old2new_lmIDs If provided, the mapping from old to new IDs is
231  * stored here. */
232  void compressIDs(
233  std::map<TCameraPoseID, TCameraPoseID>* old2new_camIDs = nullptr,
234  std::map<TLandmarkID, TLandmarkID>* old2new_lmIDs = nullptr);
235 };
236 
237 /** Parameters associated to a stereo system
238  */
240 {
241  /** Initilization of default parameters */
243 
244  void loadFromConfigFile(
246  const std::string& section) override; // See base docs
247  void dumpToTextStream(std::ostream& out) const override; // See base docs
248 
249  /** Method for propagating the feature's image coordinate uncertainty into
250  * 3D space. Default value: Prop_Linear
251  */
253  {
254  /** Linear propagation of the uncertainty
255  */
257  /** Uncertainty propagation through the Unscented Transformation
258  */
260  /** Uncertainty propagation through the Scaled Unscented Transformation
261  */
263  };
264 
266 
267  /** Stereo Fundamental matrix */
269 
270  /** Intrinsic parameters
271  */
273  /** Baseline. Default value: baseline = 0.119f; [Bumblebee]
274  */
275  float baseline{0.119f};
276  /** Standard deviation of the error in feature detection. Default value:
277  * stdPixel = 1
278  */
279  float stdPixel{1};
280  /** Standard deviation of the error in disparity computation. Default value:
281  * stdDisp = 1
282  */
283  float stdDisp{1};
284  /** Maximum allowed distance. Default value: maxZ = 20.0f
285  */
286  float maxZ{20.0f};
287  /** Maximum allowed distance. Default value: minZ = 0.5f
288  */
289  float minZ{0.5f};
290  /** Maximum allowed height. Default value: maxY = 3.0f
291  */
292  float maxY{3.0f};
293  /** K factor for the UT. Default value: k = 1.5f
294  */
295  float factor_k{1.5f};
296  /** Alpha factor for SUT. Default value: a = 1e-3
297  */
298  float factor_a{1e-3f};
299  /** Beta factor for the SUT. Default value: b = 2.0f
300  */
301  float factor_b{2.0f};
302 
303  /** Parameters initialization
304  */
305  // TStereoSystemParams();
306 
307 }; // End struct TStereoSystemParams
308 
309 /** A structure for storing a 3D ROI
310  */
311 struct TROI
312 {
313  // Constructors
314  TROI() = default;
315  TROI(float x1, float x2, float y1, float y2, float z1, float z2);
316 
317  // Members
318  float xMin{0};
319  float xMax{0};
320  float yMin{0};
321  float yMax{0};
322  float zMin{0};
323  float zMax{0};
324 }; // end struct TROI
325 
326 /** A structure for defining a ROI within an image
327  */
328 struct TImageROI
329 {
330  // Constructors
331  TImageROI() = default;
332  TImageROI(float x1, float x2, float y1, float y2);
333 
334  // Members
335  /** X coordinate limits [0,imageWidth)
336  */
337  float xMin{0}, xMax{0};
338  /** Y coordinate limits [0,imageHeight)
339  */
340  float yMin{0}, yMax{0};
341 }; // end struct TImageROI
342 
343 /** A structure containing options for the matching
344  */
346 {
347  /** Method for propagating the feature's image coordinate uncertainty into
348  * 3D space. Default value: Prop_Linear
349  */
351  {
352  /** Matching by cross correlation of the image patches
353  */
355  /** Matching by Euclidean distance between SIFT descriptors
356  */
358  /** Matching by Euclidean distance between SURF descriptors
359  */
361  /** Matching by sum of absolute differences of the image patches
362  */
364  /** Matching by Hamming distance between ORB descriptors
365  */
367  };
368 
369  // For determining
370  /** Whether or not take into account the epipolar restriction for finding
371  * correspondences */
373  /** Whether or not there is a fundamental matrix */
374  bool hasFundamentalMatrix{false};
375  /** Whether or not the stereo rig has the optical axes parallel */
377  /** Whether or not employ the x-coord restriction for finding
378  * correspondences (bumblebee camera, for example) */
379  bool useXRestriction{true};
380  /** Whether or not to add the matches found into the input matched list (if
381  * false the input list will be cleared before being filled with the new
382  * matches) */
383  bool addMatches{false};
384  /** Whether or not use limits (min,max) for the disparity, see also
385  * 'min_disp, max_disp' */
386  bool useDisparityLimits{false};
387  /** Whether or not only permit matches that are consistent from left->right
388  * and right->left */
390 
391  /** Disparity limits, see also 'useDisparityLimits' */
392  float min_disp{1.0f}, max_disp{1e4f};
393 
395 
396  // General
397  /** Matching method */
399  /** Epipolar constraint (rows of pixels) */
400  float epipolar_TH{1.5f};
401 
402  // SIFT
403  /** Maximum Euclidean Distance Between SIFT Descriptors */
404  float maxEDD_TH{90.0f};
405  /** Boundary Ratio between the two lowest EDD */
406  float EDD_RATIO{0.6f};
407 
408  // KLT
409  /** Minimum Value of the Cross Correlation */
410  float minCC_TH{0.95f};
411  /** Minimum Difference Between the Maximum Cross Correlation Values */
412  float minDCC_TH{0.025f};
413  /** Maximum Ratio Between the two highest CC values */
414  float rCC_TH{0.92f};
415 
416  // SURF
417  /** Maximum Euclidean Distance Between SURF Descriptors */
418  float maxEDSD_TH{0.15f};
419  /** Boundary Ratio between the two lowest SURF EDSD */
420  float EDSD_RATIO{0.6f};
421 
422  // SAD
423  /** Minimum Euclidean Distance Between Sum of Absolute Differences */
424  double maxSAD_TH{0.4};
425  /** Boundary Ratio between the two highest SAD */
426  double SAD_RATIO{0.5};
427 
428  // ORB
429  /** Maximun distance between ORB descriptors */
430  double maxORB_dist;
431 
432  // // To estimate depth
433  /** Whether or not estimate the 3D position of the real features for the
434  * matches (only with parallelOpticalAxis by now). */
435  bool estimateDepth{false};
436  /** The maximum allowed depth for the matching. If its computed depth is
437  * larger than this, the match won't be considered. */
438  double maxDepthThreshold{15.0};
439  /** Intrinsic parameters of the stereo rig */
440  // double fx,cx,cy,baseline;
441 
442  /** Constructor */
444 
445  void loadFromConfigFile(
447  const std::string& section) override; // See base docs
448  void dumpToTextStream(std::ostream& out) const override; // See base docs
449 
450 #define COPY_MEMBER(_m) this->_m = o._m;
451 #define CHECK_MEMBER(_m) this->_m == o._m
452 
453  bool operator==(const TMatchingOptions& o) const
454  {
455  return CHECK_MEMBER(useXRestriction) &&
470  }
471 
473  {
483  COPY_MEMBER(F)
498  }
499 
500 }; // end struct TMatchingOptions
501 
502 /** Struct containing the output after matching multi-resolution SIFT-like
503  * descriptors
504  */
506 {
507  int nMatches{0};
508 
509  /** Contains the indexes within the second list corresponding to the first
510  * one. */
511  std::vector<int> firstListCorrespondences;
512  /** Contains the indexes within the first list corresponding to the second
513  * one. */
514  std::vector<int> secondListCorrespondences;
515  /** Contains the scales of the first list where the correspondence was
516  * found. */
517  std::vector<int> firstListFoundScales;
518  /** Contains the distances between the descriptors. */
519  std::vector<double> firstListDistance;
520 
521  TMultiResMatchingOutput() = default;
522 
523 }; // end struct TMultiResMatchingOutput
524 
525 /** Struct containing the options when matching multi-resolution SIFT-like
526  * descriptors
527  */
529 {
530  /** Whether or not use the filter based on orientation test */
531  bool useOriFilter{true};
532  /** The threshold for the orientation test */
533  double oriThreshold{0.2};
534 
535  /** Whether or not use the filter based on the depth test */
536  bool useDepthFilter{true};
537 
538  /** The absolute threshold in descriptor distance for considering a match */
539  double matchingThreshold{1e4};
540  /** The ratio between the two lowest distances threshold for considering a
541  * match */
543  /** The lowest scales in the two features to be taken into account in the
544  * matching process */
546  /** The highest scales in the two features to be taken into account in the
547  * matching process */
549 
550  /** Size of the squared area where to search for a match. */
552  /** The allowed number of frames since a certain feature was seen for the
553  * last time. */
555  /** The minimum number of frames for a certain feature to be considered
556  * stable. */
558 
559  /** The minimum number of features allowed in the system. If current number
560  * is below this value, more features will be found. */
562  /** The minimum number of features allowed in the system to not be
563  * considered to be lost. */
565 
566  /** Default constructor
567  */
568  TMultiResDescMatchOptions() = default;
569 
571  const bool& _useOriFilter, const double& _oriThreshold,
572  const bool& _useDepthFilter, const double& _th, const double& _th2,
573  const unsigned int& _lwscl1, const unsigned int& _lwscl2,
574  const unsigned int& _hwscl1, const unsigned int& _hwscl2,
575  const int& _searchAreaSize, const int& _lsth, const int& _tsth,
576  const int& _minFeaturesToFind, const int& _minFeaturesToBeLost)
577  : useOriFilter(_useOriFilter),
578  oriThreshold(_oriThreshold),
579  useDepthFilter(_useDepthFilter),
580  matchingThreshold(_th),
582  lowScl1(_lwscl1),
583  lowScl2(_lwscl2),
584  highScl1(_hwscl1),
585  highScl2(_hwscl2),
586  searchAreaSize(_searchAreaSize),
587  lastSeenThreshold(_lsth),
588  timesSeenThreshold(_tsth),
589  minFeaturesToFind(_minFeaturesToFind),
590  minFeaturesToBeLost(_minFeaturesToBeLost)
591  {
592  }
593 
594  void loadFromConfigFile(
596  const std::string& section) override;
597  void saveToConfigFile(
599  const std::string& section) const override;
600  void dumpToTextStream(std::ostream& out) const override;
601 
602 }; // end TMultiResDescMatchOptions
603 
604 /** Struct containing the options when computing the multi-resolution SIFT-like
605  * descriptors
606  */
608 {
609  /** The size of the base patch */
611  /** The set of scales relatives to the base patch */
612  std::vector<double> scales;
613  /** The subset of scales for which to compute the descriptors */
615  /** The sigmas for the Gaussian kernels */
616  double sg1{0.5}, sg2{7.5}, sg3{8.0};
617  /** Whether or not to compute the depth of the feature */
618  bool computeDepth{true};
619  /** Whether or not to blur the image previously to compute the descriptors
620  */
621  bool blurImage{true};
622  /** Intrinsic stereo pair parameters for computing the depth of the feature
623  */
624  double fx{0.0}, cx{0.0}, cy{0.0}, baseline{0.0};
625  /** Whether or not compute the coefficients for mantaining a HASH table of
626  * descriptors (for relocalization) */
627  bool computeHashCoeffs{false};
628 
629  /** The SIFT-like descriptor is cropped at this value during normalization
630  */
631  double cropValue{0.2};
632 
633  /** Default constructor
634  */
636  {
637  scales.resize(7);
638  scales[0] = 0.5;
639  scales[1] = 0.8;
640  scales[2] = 1.0;
641  scales[3] = 1.2;
642  scales[4] = 1.5;
643  scales[5] = 1.8;
644  scales[6] = 2.0;
645  comLScl = 0;
646  comHScl = 6;
647  }
648 
650  const unsigned int& _basePSize, const std::vector<double>& _scales,
651  const unsigned int& _comLScl, const unsigned int& _comHScl,
652  const double& _sg1, const double& _sg2, const double& _sg3,
653  const bool& _computeDepth, const bool _blurImage, const double& _fx,
654  const double& _cx, const double& _cy, const double& _baseline,
655  const bool& _computeHashCoeffs, const double& _cropValue)
656  : basePSize(_basePSize),
657  comLScl(_comLScl),
658  comHScl(_comHScl),
659  sg1(_sg1),
660  sg2(_sg2),
661  sg3(_sg3),
662  computeDepth(_computeDepth),
663  blurImage(_blurImage),
664  fx(_fx),
665  cx(_cx),
666  cy(_cy),
667  baseline(_baseline),
668  computeHashCoeffs(_computeHashCoeffs),
669  cropValue(_cropValue)
670  {
671  scales.resize(_scales.size());
672  for (unsigned int k = 0; k < _scales.size(); ++k)
673  scales[k] = _scales[k];
674  }
675 
676  void loadFromConfigFile(
678  const std::string& section) override; // See base docs
679  void saveToConfigFile(
681  const std::string& section) const override; // See base docs
682  void dumpToTextStream(std::ostream& out) const override; // See base docs
683 
684 }; // end TMultiResDescOptions
685 
686 /** @} */ // end of grouping
687 } // namespace mrpt::vision
689 using namespace mrpt::vision;
704 
706 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.
unsigned __int16 uint16_t
Definition: rptypes.h:47
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...
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
signed char int8_t
Definition: rptypes.h:43
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).
float yMin
Y coordinate limits [0,imageHeight)
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.
unsigned char uint8_t
Definition: rptypes.h:44
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...
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...
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...
GLsizei const GLchar ** string
Definition: glext.h:4116
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...
FASTER-9 detector, Edward Rosten&#39;s libcvd, SSE2 optimized.
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.
float xMin
X coordinate limits [0,imageWidth)
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:215
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.
std::vector< double > scales
The set of scales relatives to the base patch.
unsigned __int64 uint64_t
Definition: rptypes.h:53
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:187
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.
FASTER-9 detector, Edward Rosten&#39;s libcvd, SSE2 optimized.
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:152
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].
GLsizei GLsizei GLchar * source
Definition: glext.h:4097
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)
TMultiResDescMatchOptions(const bool &_useOriFilter, const double &_oriThreshold, const bool &_useDepthFilter, const double &_th, const double &_th2, const unsigned int &_lwscl1, const unsigned int &_lwscl2, const unsigned int &_hwscl1, const unsigned int &_hwscl2, const int &_searchAreaSize, const int &_lsth, const int &_tsth, const int &_minFeaturesToFind, const int &_minFeaturesToBeLost)
GLsizeiptr size
Definition: glext.h:3934
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.
Lightweight 3D point.
Definition: TPoint3D.h:90
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.
unsigned __int32 uint32_t
Definition: rptypes.h:50
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.
TMultiResDescOptions(const unsigned int &_basePSize, const std::vector< double > &_scales, const unsigned int &_comLScl, const unsigned int &_comHScl, const double &_sg1, const double &_sg2, const double &_sg3, const bool &_computeDepth, const bool _blurImage, const double &_fx, const double &_cx, const double &_cy, const double &_baseline, const bool &_computeHashCoeffs, const double &_cropValue)
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.
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.
FASTER-9 detector, Edward Rosten&#39;s libcvd, SSE2 optimized.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019