Main MRPT website > C++ reference for 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  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
13 #include <mrpt/img/CImage.h>
18 
19 namespace mrpt
20 {
21 namespace vision
22 {
23 /** \addtogroup mrpt_vision_grp
24  * @{ */
25 /** Definition of a feature ID */
27 
28 /** Unique IDs for landmarks */
30 /** Unique IDs for camera frames (poses) */
32 
33 /** A list of camera frames (6D poses) indexed by unique IDs. */
34 using TFramePosesMap =
36 /** A list of camera frames (6D poses), which assumes indexes are unique,
37  * consecutive IDs. */
39 
40 /** A list of landmarks (3D points) indexed by unique IDs. */
41 using TLandmarkLocationsMap = std::map<TLandmarkID, mrpt::math::TPoint3D>;
42 /** A list of landmarks (3D points), which assumes indexes are unique,
43  * consecutive IDs. */
44 using TLandmarkLocationsVec = std::vector<mrpt::math::TPoint3D>;
45 
46 /** Types of features - This means that the point has been detected with this
47  * algorithm, which is independent of additional descriptors a feature may also
48  * have
49  */
51 {
52  /** Non-defined feature (also used for Occupancy features) */
54  /** Kanade-Lucas-Tomasi feature [SHI'94] */
55  featKLT = 0,
56  /** Harris border and corner detector [HARRIS] */
58  /** Binary corder detector */
60  /** Scale Invariant Feature Transform [LOWE'04] */
62  /** Speeded Up Robust Feature [BAY'06] */
64  /** A especial case: this is not an image feature, but a 2D/3D beacon (used
65  for range-only SLAM from mrpt::maps::CLandmark) */
67  /** FAST feature detector, OpenCV's implementation ("Faster and better: A
68  machine learning approach to corner detection", E. Rosten, R. Porter and
69  T. Drummond, PAMI, 2009). */
71  /** FASTER-9 detector, Edward Rosten's libcvd implementation optimized for
72  SSE2. */
74  /** FASTER-9 detector, Edward Rosten's libcvd implementation optimized for
75  SSE2. */
77  /** FASTER-9 detector, Edward Rosten's libcvd implementation optimized for
78  SSE2. */
80  /** ORB detector and descriptor, OpenCV's implementation ("ORB: an efficient
81  alternative to SIFT or SURF", E. Rublee, V. Rabaud, K. Konolige, G.
82  Bradski, ICCV, 2012). */
84  // #added by Raghavender Sahdev
85  featAKAZE, //!< AKAZE detector, OpenCV's implementation
86  featLSD //!< LSD detector, OpenCV's implementation
87  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
88 
89 };
90 
91 /** The bitwise OR combination of values of TDescriptorType are used in
92  * CFeatureExtraction::computeDescriptors to indicate which descriptors are to
93  * be computed for features.
94  */
96 {
97  /** Used in some methods to mean "any of the present descriptors" */
98  descAny = 0,
99  /** SIFT descriptors */
100  descSIFT = 1,
101  /** SURF descriptors */
102  descSURF = 2,
103  /** Intensity-domain spin image descriptors */
105  /** Polar image descriptor */
107  /** Log-Polar image descriptor */
109  /** Bit-based feature descriptor */
110  descORB = 32,
111  descBLD = 64, //!< BLD Line descriptor
112  descLATCH = 128 //!< LATCH Line descriptor
113  // Remember: If new values are added, also update MRPT_FILL_ENUM below!
114 };
115 
117 {
118  // Init value
119  /** Inactive (right after detection, and before being tried to track) */
121 
122  // Ok:
123  /** Feature correctly tracked */
125 
126  // Bad:
127  /** Feature fell Out Of Bounds (out of the image limits, too close to image
128  borders) */
130  /** Unable to track this feature (mismatch is too high for the given
131  tracking window: lack of texture? oclussion?) */
133 };
134 
135 /** One feature observation entry, used within sequences with
136  * TSequenceFeatureObservations */
138 {
141  const TLandmarkID _id_feature, const TCameraPoseID _id_frame,
142  const mrpt::img::TPixelCoordf& _px)
143  : id_feature(_id_feature), id_frame(_id_frame), px(_px)
144  {
145  }
146 
147  /** A unique ID of this feature */
149  /** A unique ID of a "frame" (camera position) from where the feature was
150  * observed. */
152  /** The pixel coordinates of the observed feature */
154 };
155 
156 /** One relative feature observation entry, used with some relative
157  * bundle-adjustment functions.
158  */
160 {
163  const mrpt::vision::TCameraPoseID _id_frame_base,
164  const mrpt::math::TPoint3D& _pos)
165  : id_frame_base(_id_frame_base), pos(_pos)
166  {
167  }
168 
169  /** The ID of the camera frame which is the coordinate reference of \a pos
170  */
172  /** The (x,y,z) location of the feature, wrt to the camera frame \a
173  * id_frame_base */
175 };
176 
177 /** An index of feature IDs and their relative locations */
179  std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos>;
180 
181 /** A complete sequence of observations of features from different camera frames
182  * (poses).
183  * This structure is the input to some (Bundle-adjustment) methods in
184  * mrpt::vision
185  * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc
186  * of functions handling this structure to see what they expect.
187  * \sa mrpt::vision::bundle_adj_full
188  */
189 struct TSequenceFeatureObservations : public std::vector<TFeatureObservation>
190 {
191  using BASE = std::vector<TFeatureObservation>;
192 
196  : BASE(o)
197  {
198  }
199 
200  /** Saves all entries to a text file, with each line having this format:
201  * #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y
202  * The file is self-descripting, since the first line contains a comment
203  * line (starting with '%') explaining the format.
204  * Generated files can be loaded from MATLAB.
205  * \sa loadFromTextFile \exception std::exception On I/O error */
206  void saveToTextFile(
207  const std::string& filName, bool skipFirstCommentLine = false) const;
208 
209  /** Load from a text file, in the format described in \a saveToTextFile
210  * \exception std::exception On I/O or format error */
211  void loadFromTextFile(const std::string& filName);
212 
213  /** Save the list of observations + the point locations + the camera frame
214  * poses to a pair of files in the format
215  * used by the Sparse Bundle Adjustment (SBA) C++ library.
216  *
217  * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
218  *
219  * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)
220  * \return false on any error
221  */
222  bool saveAsSBAFiles(
223  const TLandmarkLocationsVec& pts, const std::string& pts_file,
224  const TFramePosesVec& cams, const std::string& cams_file) const;
225 
226  /** Remove all those features that don't have a minimum number of
227  * observations from different camera frame IDs.
228  * \return the number of erased entries.
229  * \sa After calling this you may want to call \a compressIDs */
230  size_t removeFewObservedFeatures(size_t minNumObservations = 3);
231 
232  /** Remove all but one out of \a decimate_ratio camera frame IDs from the
233  * list (eg: from N camera pose IDs at return there will be just
234  * N/decimate_ratio)
235  * The algorithm first builds a sorted list of frame IDs, then keep the
236  * lowest ID, remove the next "decimate_ratio-1", and so on.
237  * \sa After calling this you may want to call \a compressIDs */
238  void decimateCameraFrames(const size_t decimate_ratio);
239 
240  /** Rearrange frame and feature IDs such as they start at 0 and there are no
241  * gaps.
242  * \param old2new_camIDs If provided, the mapping from old to new IDs is
243  * stored here.
244  * \param old2new_lmIDs If provided, the mapping from old to new IDs is
245  * stored here. */
246  void compressIDs(
247  std::map<TCameraPoseID, TCameraPoseID>* old2new_camIDs = nullptr,
248  std::map<TLandmarkID, TLandmarkID>* old2new_lmIDs = nullptr);
249 };
250 
251 /** Parameters associated to a stereo system
252  */
254 {
255  /** Initilization of default parameters */
257 
258  void loadFromConfigFile(
260  const std::string& section) override; // See base docs
261  void dumpToTextStream(std::ostream& out) const override; // See base docs
262 
263  /** Method for propagating the feature's image coordinate uncertainty into
264  * 3D space. Default value: Prop_Linear
265  */
267  {
268  /** Linear propagation of the uncertainty
269  */
271  /** Uncertainty propagation through the Unscented Transformation
272  */
274  /** Uncertainty propagation through the Scaled Unscented Transformation
275  */
277  };
278 
280 
281  /** Stereo Fundamental matrix */
283 
284  /** Intrinsic parameters
285  */
287  /** Baseline. Default value: baseline = 0.119f; [Bumblebee]
288  */
289  float baseline;
290  /** Standard deviation of the error in feature detection. Default value:
291  * stdPixel = 1
292  */
293  float stdPixel;
294  /** Standard deviation of the error in disparity computation. Default value:
295  * stdDisp = 1
296  */
297  float stdDisp;
298  /** Maximum allowed distance. Default value: maxZ = 20.0f
299  */
300  float maxZ;
301  /** Maximum allowed distance. Default value: minZ = 0.5f
302  */
303  float minZ;
304  /** Maximum allowed height. Default value: maxY = 3.0f
305  */
306  float maxY;
307  /** K factor for the UT. Default value: k = 1.5f
308  */
309  float factor_k;
310  /** Alpha factor for SUT. Default value: a = 1e-3
311  */
312  float factor_a;
313  /** Beta factor for the SUT. Default value: b = 2.0f
314  */
315  float factor_b;
316 
317  /** Parameters initialization
318  */
319  // TStereoSystemParams();
320 
321 }; // End struct TStereoSystemParams
322 
323 /** A structure for storing a 3D ROI
324  */
325 struct TROI
326 {
327  // Constructors
328  TROI();
329  TROI(float x1, float x2, float y1, float y2, float z1, float z2);
330 
331  // Members
332  float xMin;
333  float xMax;
334  float yMin;
335  float yMax;
336  float zMin;
337  float zMax;
338 }; // end struct TROI
339 
340 /** A structure for defining a ROI within an image
341  */
342 struct TImageROI
343 {
344  // Constructors
345  TImageROI();
346  TImageROI(float x1, float x2, float y1, float y2);
347 
348  // Members
349  /** X coordinate limits [0,imageWidth)
350  */
351  float xMin, xMax;
352  /** Y coordinate limits [0,imageHeight)
353  */
354  float yMin, yMax;
355 }; // end struct TImageROI
356 
357 /** A structure containing options for the matching
358  */
360 {
361  /** Method for propagating the feature's image coordinate uncertainty into
362  * 3D space. Default value: Prop_Linear
363  */
365  {
366  /** Matching by cross correlation of the image patches
367  */
369  /** Matching by Euclidean distance between SIFT descriptors
370  */
372  /** Matching by Euclidean distance between SURF descriptors
373  */
375  /** Matching by sum of absolute differences of the image patches
376  */
378  /** Matching by Hamming distance between ORB descriptors
379  */
381  };
382 
383  // For determining
384  /** Whether or not take into account the epipolar restriction for finding
385  * correspondences */
387  /** Whether or not there is a fundamental matrix */
389  /** Whether or not the stereo rig has the optical axes parallel */
391  /** Whether or not employ the x-coord restriction for finding
392  * correspondences (bumblebee camera, for example) */
394  /** Whether or not to add the matches found into the input matched list (if
395  * false the input list will be cleared before being filled with the new
396  * matches) */
398  /** Whether or not use limits (min,max) for the disparity, see also
399  * 'min_disp, max_disp' */
401  /** Whether or not only permit matches that are consistent from left->right
402  * and right->left */
404 
405  /** Disparity limits, see also 'useDisparityLimits' */
407 
409 
410  // General
411  /** Matching method */
413  /** Epipolar constraint (rows of pixels) */
414  float epipolar_TH;
415 
416  // SIFT
417  /** Maximum Euclidean Distance Between SIFT Descriptors */
418  float maxEDD_TH;
419  /** Boundary Ratio between the two lowest EDD */
420  float EDD_RATIO;
421 
422  // KLT
423  /** Minimum Value of the Cross Correlation */
424  float minCC_TH;
425  /** Minimum Difference Between the Maximum Cross Correlation Values */
426  float minDCC_TH;
427  /** Maximum Ratio Between the two highest CC values */
428  float rCC_TH;
429 
430  // SURF
431  /** Maximum Euclidean Distance Between SURF Descriptors */
432  float maxEDSD_TH;
433  /** Boundary Ratio between the two lowest SURF EDSD */
434  float EDSD_RATIO;
435 
436  // SAD
437  /** Minimum Euclidean Distance Between Sum of Absolute Differences */
438  double maxSAD_TH;
439  /** Boundary Ratio between the two highest SAD */
440  double SAD_RATIO;
441 
442  // ORB
443  /** Maximun distance between ORB descriptors */
444  double maxORB_dist;
445 
446  // // To estimate depth
447  /** Whether or not estimate the 3D position of the real features for the
448  * matches (only with parallelOpticalAxis by now). */
450  /** The maximum allowed depth for the matching. If its computed depth is
451  * larger than this, the match won't be considered. */
453  /** Intrinsic parameters of the stereo rig */
454  // double fx,cx,cy,baseline;
455 
456  /** Constructor */
458 
459  void loadFromConfigFile(
461  const std::string& section) override; // See base docs
462  void dumpToTextStream(std::ostream& out) const override; // See base docs
463 
464 #define COPY_MEMBER(_m) this->_m = o._m;
465 #define CHECK_MEMBER(_m) this->_m == o._m
466 
467  bool operator==(const TMatchingOptions& o) const
468  {
469  return CHECK_MEMBER(useXRestriction) &&
484  }
485 
487  {
497  COPY_MEMBER(F)
512  }
513 
514 }; // end struct TMatchingOptions
515 
516 /** Struct containing the output after matching multi-resolution SIFT-like
517  * descriptors
518  */
520 {
521  int nMatches;
522 
523  /** Contains the indexes within the second list corresponding to the first
524  * one. */
525  std::vector<int> firstListCorrespondences;
526  /** Contains the indexes within the first list corresponding to the second
527  * one. */
528  std::vector<int> secondListCorrespondences;
529  /** Contains the scales of the first list where the correspondence was
530  * found. */
531  std::vector<int> firstListFoundScales;
532  /** Contains the distances between the descriptors. */
533  std::vector<double> firstListDistance;
534 
536  : nMatches(0),
541  {
542  }
543 
544 }; // end struct TMultiResMatchingOutput
545 
546 /** Struct containing the options when matching multi-resolution SIFT-like
547  * descriptors
548  */
550 {
551  /** Whether or not use the filter based on orientation test */
553  /** The threshold for the orientation test */
554  double oriThreshold;
555 
556  /** Whether or not use the filter based on the depth test */
558 
559  /** The absolute threshold in descriptor distance for considering a match */
561  /** The ratio between the two lowest distances threshold for considering a
562  * match */
564  /** The lowest scales in the two features to be taken into account in the
565  * matching process */
567  /** The highest scales in the two features to be taken into account in the
568  * matching process */
570 
571  /** Size of the squared area where to search for a match. */
573  /** The allowed number of frames since a certain feature was seen for the
574  * last time. */
576  /** The minimum number of frames for a certain feature to be considered
577  * stable. */
579 
580  /** The minimum number of features allowed in the system. If current number
581  * is below this value, more features will be found. */
583  /** The minimum number of features allowed in the system to not be
584  * considered to be lost. */
586 
587  /** Default constructor
588  */
590  : useOriFilter(true),
591  oriThreshold(0.2),
592  useDepthFilter(true),
593  matchingThreshold(1e4),
595  lowScl1(0),
596  lowScl2(0),
597  highScl1(6),
598  highScl2(6),
599  searchAreaSize(20),
600  lastSeenThreshold(10),
602  minFeaturesToFind(30),
604  {
605  }
606 
608  const bool& _useOriFilter, const double& _oriThreshold,
609  const bool& _useDepthFilter, const double& _th, const double& _th2,
610  const unsigned int& _lwscl1, const unsigned int& _lwscl2,
611  const unsigned int& _hwscl1, const unsigned int& _hwscl2,
612  const int& _searchAreaSize, const int& _lsth, const int& _tsth,
613  const int& _minFeaturesToFind, const int& _minFeaturesToBeLost)
614  : useOriFilter(_useOriFilter),
615  oriThreshold(_oriThreshold),
616  useDepthFilter(_useDepthFilter),
617  matchingThreshold(_th),
619  lowScl1(_lwscl1),
620  lowScl2(_lwscl2),
621  highScl1(_hwscl1),
622  highScl2(_hwscl2),
623  searchAreaSize(_searchAreaSize),
624  lastSeenThreshold(_lsth),
625  timesSeenThreshold(_tsth),
626  minFeaturesToFind(_minFeaturesToFind),
627  minFeaturesToBeLost(_minFeaturesToBeLost)
628  {
629  }
630 
631  void loadFromConfigFile(
633  const std::string& section) override;
634  void saveToConfigFile(
636  const std::string& section) const override;
637  void dumpToTextStream(std::ostream& out) const override;
638 
639 }; // end TMultiResDescMatchOptions
640 
641 /** Struct containing the options when computing the multi-resolution SIFT-like
642  * descriptors
643  */
645 {
646  /** The size of the base patch */
648  /** The set of scales relatives to the base patch */
649  std::vector<double> scales;
650  /** The subset of scales for which to compute the descriptors */
652  /** The sigmas for the Gaussian kernels */
653  double sg1, sg2, sg3;
654  /** Whether or not to compute the depth of the feature */
656  /** Whether or not to blur the image previously to compute the descriptors
657  */
658  bool blurImage;
659  /** Intrinsic stereo pair parameters for computing the depth of the feature
660  */
661  double fx, cx, cy, baseline;
662  /** Whether or not compute the coefficients for mantaining a HASH table of
663  * descriptors (for relocalization) */
665 
666  /** The SIFT-like descriptor is cropped at this value during normalization
667  */
668  double cropValue;
669 
670  /** Default constructor
671  */
673  : basePSize(23),
674  sg1(0.5),
675  sg2(7.5),
676  sg3(8.0),
677  computeDepth(true),
678  blurImage(true),
679  fx(0.0),
680  cx(0.0),
681  cy(0.0),
682  baseline(0.0),
683  computeHashCoeffs(false),
684  cropValue(0.2)
685  {
686  scales.resize(7);
687  scales[0] = 0.5;
688  scales[1] = 0.8;
689  scales[2] = 1.0;
690  scales[3] = 1.2;
691  scales[4] = 1.5;
692  scales[5] = 1.8;
693  scales[6] = 2.0;
694  comLScl = 0;
695  comHScl = 6;
696  }
697 
699  const unsigned int& _basePSize, const std::vector<double>& _scales,
700  const unsigned int& _comLScl, const unsigned int& _comHScl,
701  const double& _sg1, const double& _sg2, const double& _sg3,
702  const bool& _computeDepth, const bool _blurImage, const double& _fx,
703  const double& _cx, const double& _cy, const double& _baseline,
704  const bool& _computeHashCoeffs, const double& _cropValue)
705  : basePSize(_basePSize),
706  comLScl(_comLScl),
707  comHScl(_comHScl),
708  sg1(_sg1),
709  sg2(_sg2),
710  sg3(_sg3),
711  computeDepth(_computeDepth),
712  blurImage(_blurImage),
713  fx(_fx),
714  cx(_cx),
715  cy(_cy),
716  baseline(_baseline),
717  computeHashCoeffs(_computeHashCoeffs),
718  cropValue(_cropValue)
719  {
720  scales.resize(_scales.size());
721  for (unsigned int k = 0; k < _scales.size(); ++k)
722  scales[k] = _scales[k];
723  }
724 
725  void loadFromConfigFile(
727  const std::string& section) override; // See base docs
728  void saveToConfigFile(
730  const std::string& section) const override; // See base docs
731  void dumpToTextStream(std::ostream& out) const override; // See base docs
732 
733 }; // end TMultiResDescOptions
734 
735 /** @} */ // end of grouping
736 } // namespace vision
737 } // namespace mrpt
738 
740 using namespace mrpt::vision;
756 
758 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:51
float rCC_TH
Maximum Ratio Between the two highest CC values.
TLandmarkID id_feature
A unique ID of this feature.
Non-defined feature (also used for Occupancy features)
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...
Used in some methods to mean "any of the present descriptors".
bool estimateDepth
Whether or not estimate the 3D position of the real features for the matches (only with parallelOptic...
LSD detector, OpenCV&#39;s implementation.
uint64_t TLandmarkID
Unique IDs for landmarks.
bool useXRestriction
Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera...
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
double SAD_RATIO
Boundary Ratio between the two highest SAD.
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.
float min_disp
Disparity limits, see also &#39;useDisparityLimits&#39;.
Struct containing the output after matching multi-resolution SIFT-like descriptors.
One feature observation entry, used within sequences with TSequenceFeatureObservations.
#define CHECK_MEMBER(_m)
TSequenceFeatureObservations(const TSequenceFeatureObservations &o)
A pair (x,y) of pixel coordinates (subpixel resolution).
Definition: TPixelCoord.h:20
std::vector< int > secondListCorrespondences
Contains the indexes within the first list corresponding to the second one.
float epipolar_TH
Epipolar constraint (rows of pixels)
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::map< KEY, VALUE, std::less< KEY >, mrpt::aligned_allocator_cpp11< std::pair< const KEY, VALUE > >> aligned_std_map
std::vector< double > firstListDistance
Contains the distances between the descriptors.
Matching by Hamming distance between ORB descriptors.
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
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:69
MRPT_FILL_ENUM(featNotDefined)
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.
FAST feature detector, OpenCV&#39;s implementation ("Faster and better: A machine learning approac...
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.
Inactive (right after detection, and before being tried to track)
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.
bool parallelOpticalAxis
Whether or not the stereo rig has the optical axes parallel.
float minDCC_TH
Minimum Difference Between the Maximum Cross Correlation Values.
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.
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.
Harris border and corner detector [HARRIS].
bool useDepthFilter
Whether or not use the filter based on the depth test.
Scale Invariant Feature Transform [LOWE&#39;04].
Matching by Euclidean distance between SURF descriptors.
std::map< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
Classes for computer vision, detectors, features, etc.
Definition: CCamModel.h:20
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:30
std::vector< int > firstListCorrespondences
Contains the indexes within the second list corresponding to the first one.
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:74
double maxDepthThreshold
The maximum allowed depth for the matching.
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
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
Bit-based feature descriptor.
One relative feature observation entry, used with some relative bundle-adjustment functions...
GLsizei const GLchar ** string
Definition: glext.h:4101
double cropValue
The SIFT-like descriptor is cropped at this value during normalization.
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.
TDescriptorType
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...
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:214
TFeatureType
Types of features - This means that the point has been detected with this algorithm, which is independent of additional descriptors a feature may also have.
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.
Unable to track this feature (mismatch is too high for the given tracking window: lack of texture...
std::vector< double > scales
The set of scales relatives to the base patch.
unsigned __int64 uint64_t
Definition: rptypes.h:50
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:186
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.
#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:102
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:151
bool enable_robust_1to1_match
Whether or not only permit matches that are consistent from left->right and right->left.
Speeded Up Robust Feature [BAY&#39;06].
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:40
Matching by cross correlation of the image patches.
mrpt::aligned_std_vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
bool hasFundamentalMatrix
Whether or not there is a fundamental matrix.
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
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:143
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.
Intensity-domain spin image descriptors.
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.
mrpt::aligned_std_map< TCameraPoseID, mrpt::poses::CPose3D > TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
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)
AKAZE detector, OpenCV&#39;s implementation.
A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt...
GLsizeiptr size
Definition: glext.h:3923
bool operator==(const TMatchingOptions &o) const
ORB detector and descriptor, OpenCV&#39;s implementation ("ORB: an efficient alternative to SIFT o...
uint32_t minFeaturesToBeLost
The minimum number of features allowed in the system to not be considered to be lost.
Lightweight 3D point.
Feature fell Out Of Bounds (out of the image limits, too close to image borders)
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:58
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:47
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.
Kanade-Lucas-Tomasi feature [SHI&#39;94].
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:207
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:172
float stdDisp
Standard deviation of the error in disparity computation.
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at lun oct 28 00:14:14 CET 2019