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-2017, 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 
10 #ifndef mrpt_vision_types_H
11 #define mrpt_vision_types_H
12 
14 #include <mrpt/utils/CImage.h>
18 #include <mrpt/utils/TEnumType.h>
19 
20 namespace mrpt
21 {
22 namespace vision
23 {
24 /** \addtogroup mrpt_vision_grp
25  * @{ */
26 /** Definition of a feature ID */
28 
29 /** Unique IDs for landmarks */
31 /** Unique IDs for camera frames (poses) */
33 
34 /** A list of camera frames (6D poses) indexed by unique IDs. */
37 /** A list of camera frames (6D poses), which assumes indexes are unique,
38  * consecutive IDs. */
40 
41 /** A list of landmarks (3D points) indexed by unique IDs. */
42 typedef std::map<TLandmarkID, mrpt::math::TPoint3D> TLandmarkLocationsMap;
43 /** A list of landmarks (3D points), which assumes indexes are unique,
44  * consecutive IDs. */
45 typedef std::vector<mrpt::math::TPoint3D> TLandmarkLocationsVec;
46 
47 /** Types of features - This means that the point has been detected with this
48  * algorithm, which is independent of additional descriptors a feature may also
49  * have
50 */
52 {
53  /** Non-defined feature (also used for Occupancy features) */
55  /** Kanade-Lucas-Tomasi feature [SHI'94] */
56  featKLT = 0,
57  /** Harris border and corner detector [HARRIS] */
59  /** Binary corder detector */
61  /** Scale Invariant Feature Transform [LOWE'04] */
63  /** Speeded Up Robust Feature [BAY'06] */
65  /** A especial case: this is not an image feature, but a 2D/3D beacon (used
66  for range-only SLAM from mrpt::maps::CLandmark) */
68  /** FAST feature detector, OpenCV's implementation ("Faster and better: A
69  machine learning approach to corner detection", E. Rosten, R. Porter and
70  T. Drummond, PAMI, 2009). */
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  /** FASTER-9 detector, Edward Rosten's libcvd implementation optimized for
79  SSE2. */
81  /** ORB detector and descriptor, OpenCV's implementation ("ORB: an efficient
82  alternative to SIFT or SURF", E. Rublee, V. Rabaud, K. Konolige, G.
83  Bradski, ICCV, 2012). */
85  // #added by Raghavender Sahdev
86  featAKAZE, //!< AKAZE detector, OpenCV's implementation
87  featLSD //!< LSD detector, OpenCV's implementation
88  // Remember: If new values are added, also update TEnumTypeFiller below!
89 
90 };
91 
92 /** The bitwise OR combination of values of TDescriptorType are used in
93  * CFeatureExtraction::computeDescriptors to indicate which descriptors are to
94  * be computed for features.
95  */
97 {
98  /** Used in some methods to mean "any of the present descriptors" */
99  descAny = 0,
100  /** SIFT descriptors */
101  descSIFT = 1,
102  /** SURF descriptors */
103  descSURF = 2,
104  /** Intensity-domain spin image descriptors */
106  /** Polar image descriptor */
108  /** Log-Polar image descriptor */
110  /** Bit-based feature descriptor */
111  descORB = 32,
112  // Remember: If new values are added, also update TEnumTypeFiller below!
113  // #added by Raghavender Sahdev
114  descBLD = 64, //!< BLD Line descriptor
115  descLATCH = 128 //!< LATCH Line descriptor
116 };
117 
119 {
120  // Init value
121  /** Inactive (right after detection, and before being tried to track) */
123 
124  // Ok:
125  /** Feature correctly tracked */
127 
128  // Bad:
129  /** Feature fell Out Of Bounds (out of the image limits, too close to image
130  borders) */
132  /** Unable to track this feature (mismatch is too high for the given
133  tracking window: lack of texture? oclussion?) */
135 };
136 
137 /** One feature observation entry, used within sequences with
138  * TSequenceFeatureObservations */
140 {
143  const TLandmarkID _id_feature, const TCameraPoseID _id_frame,
144  const mrpt::utils::TPixelCoordf& _px)
145  : id_feature(_id_feature), id_frame(_id_frame), px(_px)
146  {
147  }
148 
149  /** A unique ID of this feature */
151  /** A unique ID of a "frame" (camera position) from where the feature was
152  * observed. */
154  /** The pixel coordinates of the observed feature */
156 };
157 
158 /** One relative feature observation entry, used with some relative
159  * bundle-adjustment functions.
160  */
162 {
165  const mrpt::vision::TCameraPoseID _id_frame_base,
166  const mrpt::math::TPoint3D& _pos)
167  : id_frame_base(_id_frame_base), pos(_pos)
168  {
169  }
170 
171  /** The ID of the camera frame which is the coordinate reference of \a pos
172  */
174  /** The (x,y,z) location of the feature, wrt to the camera frame \a
175  * id_frame_base */
177 };
178 
179 /** An index of feature IDs and their relative locations */
180 typedef std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos>
182 
183 /** A complete sequence of observations of features from different camera frames
184  * (poses).
185  * This structure is the input to some (Bundle-adjustment) methods in
186  * mrpt::vision
187  * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc
188  * of functions handling this structure to see what they expect.
189  * \sa mrpt::vision::bundle_adj_full
190  */
191 struct TSequenceFeatureObservations : public std::vector<TFeatureObservation>
192 {
193  typedef std::vector<TFeatureObservation> BASE;
194 
198  : BASE(o)
199  {
200  }
201 
202  /** Saves all entries to a text file, with each line having this format:
203  * #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y
204  * The file is self-descripting, since the first line contains a comment
205  * line (starting with '%') explaining the format.
206  * Generated files can be loaded from MATLAB.
207  * \sa loadFromTextFile \exception std::exception On I/O error */
208  void saveToTextFile(
209  const std::string& filName, bool skipFirstCommentLine = false) const;
210 
211  /** Load from a text file, in the format described in \a saveToTextFile
212  * \exception std::exception On I/O or format error */
213  void loadFromTextFile(const std::string& filName);
214 
215  /** Save the list of observations + the point locations + the camera frame
216  * poses to a pair of files in the format
217  * used by the Sparse Bundle Adjustment (SBA) C++ library.
218  *
219  * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
220  *
221  * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)
222  * \return false on any error
223  */
224  bool saveAsSBAFiles(
225  const TLandmarkLocationsVec& pts, const std::string& pts_file,
226  const TFramePosesVec& cams, const std::string& cams_file) const;
227 
228  /** Remove all those features that don't have a minimum number of
229  * observations from different camera frame IDs.
230  * \return the number of erased entries.
231  * \sa After calling this you may want to call \a compressIDs */
232  size_t removeFewObservedFeatures(size_t minNumObservations = 3);
233 
234  /** Remove all but one out of \a decimate_ratio camera frame IDs from the
235  * list (eg: from N camera pose IDs at return there will be just
236  * N/decimate_ratio)
237  * The algorithm first builds a sorted list of frame IDs, then keep the
238  * lowest ID, remove the next "decimate_ratio-1", and so on.
239  * \sa After calling this you may want to call \a compressIDs */
240  void decimateCameraFrames(const size_t decimate_ratio);
241 
242  /** Rearrange frame and feature IDs such as they start at 0 and there are no
243  * gaps.
244  * \param old2new_camIDs If provided, the mapping from old to new IDs is
245  * stored here.
246  * \param old2new_lmIDs If provided, the mapping from old to new IDs is
247  * stored here. */
248  void compressIDs(
249  std::map<TCameraPoseID, TCameraPoseID>* old2new_camIDs = nullptr,
250  std::map<TLandmarkID, TLandmarkID>* old2new_lmIDs = nullptr);
251 };
252 
253 /** Parameters associated to a stereo system
254  */
256 {
257  /** Initilization of default parameters */
259 
260  void loadFromConfigFile(
262  const std::string& section) override; // See base docs
263  void dumpToTextStream(
264  mrpt::utils::CStream& out) const override; // See base docs
265 
266  /** Method for propagating the feature's image coordinate uncertainty into
267  * 3D space. Default value: Prop_Linear
268  */
270  {
271  /** Linear propagation of the uncertainty
272  */
274  /** Uncertainty propagation through the Unscented Transformation
275  */
277  /** Uncertainty propagation through the Scaled Unscented Transformation
278  */
280  };
281 
283 
284  /** Stereo Fundamental matrix */
286 
287  /** Intrinsic parameters
288  */
290  /** Baseline. Default value: baseline = 0.119f; [Bumblebee]
291  */
292  float baseline;
293  /** Standard deviation of the error in feature detection. Default value:
294  * stdPixel = 1
295  */
296  float stdPixel;
297  /** Standard deviation of the error in disparity computation. Default value:
298  * stdDisp = 1
299  */
300  float stdDisp;
301  /** Maximum allowed distance. Default value: maxZ = 20.0f
302  */
303  float maxZ;
304  /** Maximum allowed distance. Default value: minZ = 0.5f
305  */
306  float minZ;
307  /** Maximum allowed height. Default value: maxY = 3.0f
308  */
309  float maxY;
310  /** K factor for the UT. Default value: k = 1.5f
311  */
312  float factor_k;
313  /** Alpha factor for SUT. Default value: a = 1e-3
314  */
315  float factor_a;
316  /** Beta factor for the SUT. Default value: b = 2.0f
317  */
318  float factor_b;
319 
320  /** Parameters initialization
321  */
322  // TStereoSystemParams();
323 
324 }; // End struct TStereoSystemParams
325 
326 /** A structure for storing a 3D ROI
327  */
328 struct TROI
329 {
330  // Constructors
331  TROI();
332  TROI(float x1, float x2, float y1, float y2, float z1, float z2);
333 
334  // Members
335  float xMin;
336  float xMax;
337  float yMin;
338  float yMax;
339  float zMin;
340  float zMax;
341 }; // end struct TROI
342 
343 /** A structure for defining a ROI within an image
344  */
345 struct TImageROI
346 {
347  // Constructors
348  TImageROI();
349  TImageROI(float x1, float x2, float y1, float y2);
350 
351  // Members
352  /** X coordinate limits [0,imageWidth)
353  */
354  float xMin, xMax;
355  /** Y coordinate limits [0,imageHeight)
356  */
357  float yMin, yMax;
358 }; // end struct TImageROI
359 
360 /** A structure containing options for the matching
361  */
363 {
364  /** Method for propagating the feature's image coordinate uncertainty into
365  * 3D space. Default value: Prop_Linear
366  */
368  {
369  /** Matching by cross correlation of the image patches
370  */
372  /** Matching by Euclidean distance between SIFT descriptors
373  */
375  /** Matching by Euclidean distance between SURF descriptors
376  */
378  /** Matching by sum of absolute differences of the image patches
379  */
381  /** Matching by Hamming distance between ORB descriptors
382  */
384  };
385 
386  // For determining
387  /** Whether or not take into account the epipolar restriction for finding
388  * correspondences */
390  /** Whether or not there is a fundamental matrix */
392  /** Whether or not the stereo rig has the optical axes parallel */
394  /** Whether or not employ the x-coord restriction for finding
395  * correspondences (bumblebee camera, for example) */
397  /** Whether or not to add the matches found into the input matched list (if
398  * false the input list will be cleared before being filled with the new
399  * matches) */
401  /** Whether or not use limits (min,max) for the disparity, see also
402  * 'min_disp, max_disp' */
404  /** Whether or not only permit matches that are consistent from left->right
405  * and right->left */
407 
408  /** Disparity limits, see also 'useDisparityLimits' */
410 
412 
413  // General
414  /** Matching method */
416  /** Epipolar constraint (rows of pixels) */
417  float epipolar_TH;
418 
419  // SIFT
420  /** Maximum Euclidean Distance Between SIFT Descriptors */
421  float maxEDD_TH;
422  /** Boundary Ratio between the two lowest EDD */
423  float EDD_RATIO;
424 
425  // KLT
426  /** Minimum Value of the Cross Correlation */
427  float minCC_TH;
428  /** Minimum Difference Between the Maximum Cross Correlation Values */
429  float minDCC_TH;
430  /** Maximum Ratio Between the two highest CC values */
431  float rCC_TH;
432 
433  // SURF
434  /** Maximum Euclidean Distance Between SURF Descriptors */
435  float maxEDSD_TH;
436  /** Boundary Ratio between the two lowest SURF EDSD */
437  float EDSD_RATIO;
438 
439  // SAD
440  /** Minimum Euclidean Distance Between Sum of Absolute Differences */
441  double maxSAD_TH;
442  /** Boundary Ratio between the two highest SAD */
443  double SAD_RATIO;
444 
445  // ORB
446  /** Maximun distance between ORB descriptors */
447  double maxORB_dist;
448 
449  // // To estimate depth
450  /** Whether or not estimate the 3D position of the real features for the
451  * matches (only with parallelOpticalAxis by now). */
453  /** The maximum allowed depth for the matching. If its computed depth is
454  * larger than this, the match won't be considered. */
456  /** Intrinsic parameters of the stereo rig */
457  // double fx,cx,cy,baseline;
458 
459  /** Constructor */
461 
462  void loadFromConfigFile(
464  const std::string& section) override; // See base docs
465  void dumpToTextStream(
466  mrpt::utils::CStream& out) const override; // See base docs
467 
468 #define COPY_MEMBER(_m) this->_m = o._m;
469 #define CHECK_MEMBER(_m) this->_m == o._m
470 
471  bool operator==(const TMatchingOptions& o) const
472  {
473  return CHECK_MEMBER(useXRestriction) &&
488  }
489 
491  {
501  COPY_MEMBER(F)
516  }
517 
518 }; // end struct TMatchingOptions
519 
520 /** Struct containing the output after matching multi-resolution SIFT-like
521  * descriptors
522 */
524 {
525  int nMatches;
526 
527  /** Contains the indexes within the second list corresponding to the first
528  * one. */
529  std::vector<int> firstListCorrespondences;
530  /** Contains the indexes within the first list corresponding to the second
531  * one. */
532  std::vector<int> secondListCorrespondences;
533  /** Contains the scales of the first list where the correspondence was
534  * found. */
535  std::vector<int> firstListFoundScales;
536  /** Contains the distances between the descriptors. */
537  std::vector<double> firstListDistance;
538 
540  : nMatches(0),
545  {
546  }
547 
548 }; // end struct TMultiResMatchingOutput
549 
550 /** Struct containing the options when matching multi-resolution SIFT-like
551  * descriptors
552 */
554 {
555  /** Whether or not use the filter based on orientation test */
557  /** The threshold for the orientation test */
558  double oriThreshold;
559 
560  /** Whether or not use the filter based on the depth test */
562 
563  /** The absolute threshold in descriptor distance for considering a match */
565  /** The ratio between the two lowest distances threshold for considering a
566  * match */
568  /** The lowest scales in the two features to be taken into account in the
569  * matching process */
571  /** The highest scales in the two features to be taken into account in the
572  * matching process */
574 
575  /** Size of the squared area where to search for a match. */
577  /** The allowed number of frames since a certain feature was seen for the
578  * last time. */
580  /** The minimum number of frames for a certain feature to be considered
581  * stable. */
583 
584  /** The minimum number of features allowed in the system. If current number
585  * is below this value, more features will be found. */
587  /** The minimum number of features allowed in the system to not be
588  * considered to be lost. */
590 
591  /** Default constructor
592  */
594  : useOriFilter(true),
595  oriThreshold(0.2),
596  useDepthFilter(true),
597  matchingThreshold(1e4),
599  lowScl1(0),
600  lowScl2(0),
601  highScl1(6),
602  highScl2(6),
603  searchAreaSize(20),
604  lastSeenThreshold(10),
606  minFeaturesToFind(30),
608  {
609  }
610 
612  const bool& _useOriFilter, const double& _oriThreshold,
613  const bool& _useDepthFilter, const double& _th, const double& _th2,
614  const unsigned int& _lwscl1, const unsigned int& _lwscl2,
615  const unsigned int& _hwscl1, const unsigned int& _hwscl2,
616  const int& _searchAreaSize, const int& _lsth, const int& _tsth,
617  const int& _minFeaturesToFind, const int& _minFeaturesToBeLost)
618  : useOriFilter(_useOriFilter),
619  oriThreshold(_oriThreshold),
620  useDepthFilter(_useDepthFilter),
621  matchingThreshold(_th),
623  lowScl1(_lwscl1),
624  lowScl2(_lwscl2),
625  highScl1(_hwscl1),
626  highScl2(_hwscl2),
627  searchAreaSize(_searchAreaSize),
628  lastSeenThreshold(_lsth),
629  timesSeenThreshold(_tsth),
630  minFeaturesToFind(_minFeaturesToFind),
631  minFeaturesToBeLost(_minFeaturesToBeLost)
632  {
633  }
634 
635  void loadFromConfigFile(
636  const mrpt::utils::CConfigFileBase& cfg,
637  const std::string& section) override;
638  void saveToConfigFile(
640  const std::string& section) const override;
641  void dumpToTextStream(mrpt::utils::CStream& out) const override;
642 
643 }; // end TMultiResDescMatchOptions
644 
645 /** Struct containing the options when computing the multi-resolution SIFT-like
646  * descriptors
647 */
649 {
650  /** The size of the base patch */
652  /** The set of scales relatives to the base patch */
653  std::vector<double> scales;
654  /** The subset of scales for which to compute the descriptors */
656  /** The sigmas for the Gaussian kernels */
657  double sg1, sg2, sg3;
658  /** Whether or not to compute the depth of the feature */
660  /** Whether or not to blur the image previously to compute the descriptors
661  */
662  bool blurImage;
663  /** Intrinsic stereo pair parameters for computing the depth of the feature
664  */
665  double fx, cx, cy, baseline;
666  /** Whether or not compute the coefficients for mantaining a HASH table of
667  * descriptors (for relocalization) */
669 
670  /** The SIFT-like descriptor is cropped at this value during normalization
671  */
672  double cropValue;
673 
674  /** Default constructor
675  */
677  : basePSize(23),
678  sg1(0.5),
679  sg2(7.5),
680  sg3(8.0),
681  computeDepth(true),
682  blurImage(true),
683  fx(0.0),
684  cx(0.0),
685  cy(0.0),
686  baseline(0.0),
687  computeHashCoeffs(false),
688  cropValue(0.2)
689  {
690  scales.resize(7);
691  scales[0] = 0.5;
692  scales[1] = 0.8;
693  scales[2] = 1.0;
694  scales[3] = 1.2;
695  scales[4] = 1.5;
696  scales[5] = 1.8;
697  scales[6] = 2.0;
698  comLScl = 0;
699  comHScl = 6;
700  }
701 
703  const unsigned int& _basePSize, const std::vector<double>& _scales,
704  const unsigned int& _comLScl, const unsigned int& _comHScl,
705  const double& _sg1, const double& _sg2, const double& _sg3,
706  const bool& _computeDepth, const bool _blurImage, const double& _fx,
707  const double& _cx, const double& _cy, const double& _baseline,
708  const bool& _computeHashCoeffs, const double& _cropValue)
709  : basePSize(_basePSize),
710  comLScl(_comLScl),
711  comHScl(_comHScl),
712  sg1(_sg1),
713  sg2(_sg2),
714  sg3(_sg3),
715  computeDepth(_computeDepth),
716  blurImage(_blurImage),
717  fx(_fx),
718  cx(_cx),
719  cy(_cy),
720  baseline(_baseline),
721  computeHashCoeffs(_computeHashCoeffs),
722  cropValue(_cropValue)
723  {
724  scales.resize(_scales.size());
725  for (unsigned int k = 0; k < _scales.size(); ++k)
726  scales[k] = _scales[k];
727  }
728 
729  void loadFromConfigFile(
731  const std::string& section) override; // See base docs
732  void saveToConfigFile(
734  const std::string& section) const override; // See base docs
735  void dumpToTextStream(
736  mrpt::utils::CStream& out) const override; // See base docs
737 
738 }; // end TMultiResDescOptions
739 
740 /** @} */ // end of grouping
741 }
742 // Specializations MUST occur at the same namespace:
743 namespace utils
744 {
745 template <>
747 {
749  static void fill(bimap<enum_t, std::string>& m_map)
750  {
751  using namespace mrpt::vision;
766  }
767 };
768 template <>
770 {
772  static void fill(bimap<enum_t, std::string>& m_map)
773  {
774  using namespace mrpt::vision;
784  }
785 };
786 }
787 }
788 #endif
TUnc_Prop_Method
Method for propagating the feature&#39;s image coordinate uncertainty into 3D space.
A pair (x,y) of pixel coordinates (subpixel resolution).
Definition: TPixelCoord.h:21
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.
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)
mrpt::math::CMatrixDouble33 F
Stereo Fundamental matrix.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
Load all the params from a config source, in the format described in saveToConfigFile() ...
Definition: CFeature.cpp:144
mrpt::aligned_containers< TCameraPoseID, mrpt::poses::CPose3D >::map_t TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
uint32_t minFeaturesToFind
The minimum number of features allowed in the system.
void operator=(const TMatchingOptions &o)
double maxORB_dist
Maximun distance between ORB descriptors.
Used in some methods to mean "any of the present descriptors".
void saveToConfigFile(mrpt::utils::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:179
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.
std::map< mrpt::vision::TFeatureID, TRelativeFeaturePos > TRelativeFeaturePosMap
An index of feature IDs and their relative locations.
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.
INT32 z2
Definition: jidctint.cpp:130
double SAD_RATIO
Boundary Ratio between the two highest SAD.
float min_disp
Disparity limits, see also &#39;useDisparityLimits&#39;.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
Definition: CFeature.cpp:207
Struct containing the output after matching multi-resolution SIFT-like descriptors.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
#define MRPT_FILL_ENUM(_X)
For use in specializations of TEnumTypeFiller.
Definition: TEnumType.h:31
One feature observation entry, used within sequences with TSequenceFeatureObservations.
#define CHECK_MEMBER(_m)
TSequenceFeatureObservations(const TSequenceFeatureObservations &o)
std::vector< int > secondListCorrespondences
Contains the indexes within the first list corresponding to the second one.
float epipolar_TH
Epipolar constraint (rows of pixels)
Only specializations of this class are defined for each enum type of interest.
Definition: TEnumType.h:24
uint32_t highScl1
The highest scales in the two features to be taken into account in the matching process.
void saveToConfigFile(mrpt::utils::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:68
float EDSD_RATIO
Boundary Ratio between the two lowest SURF EDSD.
mrpt::utils::TPixelCoordf px
The pixel coordinates of the observed feature.
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.
TFeatureObservation(const TLandmarkID _id_feature, const TCameraPoseID _id_frame, const mrpt::utils::TPixelCoordf &_px)
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
Definition: CFeature.cpp:101
A complete sequence of observations of features from different camera frames (poses).
This class allows loading and storing values and vectors of different types from a configuration text...
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.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &cfg, const std::string &section) override
Load all the params from a config source, in the format described in saveToConfigFile() ...
Definition: CFeature.cpp:39
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.
mrpt::aligned_containers< mrpt::poses::CPose3D >::vector_t TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
bool parallelOpticalAxis
Whether or not the stereo rig has the optical axes parallel.
float minDCC_TH
Minimum Difference Between the Maximum Cross Correlation Values.
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.
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.
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
Definition: bimap.h:34
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
Classes for computer vision, detectors, features, etc.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
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...
std::vector< int > firstListCorrespondences
Contains the indexes within the second list corresponding to the first one.
double maxDepthThreshold
The maximum allowed depth for the matching.
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
uint64_t TFeatureID
Definition of a feature ID.
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...
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.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
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)
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
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
uint64_t TLandmarkID
Unique IDs for landmarks.
bool computeDepth
Whether or not to compute the depth of the feature.
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.
TRelativeFeaturePos(const mrpt::vision::TCameraPoseID _id_frame_base, const mrpt::math::TPoint3D &_pos)
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.
Matching by cross correlation of the image patches.
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...
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
Struct containing the options when matching multi-resolution SIFT-like descriptors.
float maxEDSD_TH
Maximum Euclidean Distance Between SURF Descriptors.
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
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.
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
std::map< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
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)
TMatchingMethod matching_method
Matching method.
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
Kanade-Lucas-Tomasi feature [SHI&#39;94].
bool blurImage
Whether or not to blur the image previously to compute the descriptors.
INT32 z1
Definition: jidctint.cpp:130
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)
std::vector< TYPE1, Eigen::aligned_allocator< TYPE1 > > vector_t
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.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
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...
float stdDisp
Standard deviation of the error in disparity computation.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019