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