Main MRPT website > C++ reference for MRPT 1.5.6
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 
20 
21 namespace mrpt
22 {
23  namespace vision
24  {
25  /** \addtogroup mrpt_vision_grp
26  * @{ */
27  typedef uint64_t TFeatureID; //!< Definition of a feature ID
28 
29  typedef uint64_t TLandmarkID; //!< Unique IDs for landmarks
30  typedef uint64_t TCameraPoseID; //!< Unique IDs for camera frames (poses)
31 
32  typedef mrpt::aligned_containers<TCameraPoseID,mrpt::poses::CPose3D>::map_t TFramePosesMap; //!< A list of camera frames (6D poses) indexed by unique IDs.
33  typedef mrpt::aligned_containers<mrpt::poses::CPose3D>::vector_t TFramePosesVec; //!< A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs.
34 
35  typedef std::map<TLandmarkID,mrpt::math::TPoint3D> TLandmarkLocationsMap; //!< A list of landmarks (3D points) indexed by unique IDs.
36  typedef std::vector<mrpt::math::TPoint3D> TLandmarkLocationsVec; //!< A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
37 
38 
39  /** 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
40  */
42  {
43  featNotDefined = -1, //!< Non-defined feature (also used for Occupancy features)
44  featKLT = 0, //!< Kanade-Lucas-Tomasi feature [SHI'94]
45  featHarris, //!< Harris border and corner detector [HARRIS]
46  featBCD, //!< Binary corder detector
47  featSIFT, //!< Scale Invariant Feature Transform [LOWE'04]
48  featSURF, //!< Speeded Up Robust Feature [BAY'06]
49  featBeacon, //!< A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt::maps::CLandmark)
50  featFAST, //!< FAST feature detector, OpenCV's implementation ("Faster and better: A machine learning approach to corner detection", E. Rosten, R. Porter and T. Drummond, PAMI, 2009).
51  featFASTER9, //!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.
52  featFASTER10, //!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.
53  featFASTER12, //!< FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2.
54  featORB //!< ORB detector and descriptor, OpenCV's implementation ("ORB: an efficient alternative to SIFT or SURF", E. Rublee, V. Rabaud, K. Konolige, G. Bradski, ICCV, 2012).
55  };
56 
57  /** The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescriptors to indicate which descriptors are to be computed for features.
58  */
60  {
61  descAny = 0, //!< Used in some methods to mean "any of the present descriptors"
62  descSIFT = 1, //!< SIFT descriptors
63  descSURF = 2, //!< SURF descriptors
64  descSpinImages = 4, //!< Intensity-domain spin image descriptors
65  descPolarImages = 8, //!< Polar image descriptor
66  descLogPolarImages = 16, //!< Log-Polar image descriptor
67  descORB = 32 //!< Bit-based feature descriptor
68  };
69 
71  {
72  // Init value
73  status_IDLE = 0, //!< Inactive (right after detection, and before being tried to track)
74 
75  // Ok:
76  status_TRACKED = 5, //!< Feature correctly tracked
77 
78  // Bad:
79  status_OOB = 1, //!< Feature fell Out Of Bounds (out of the image limits, too close to image borders)
80  status_LOST = 10 //!< Unable to track this feature (mismatch is too high for the given tracking window: lack of texture? oclussion?)
81  };
82 
83 
84  /** One feature observation entry, used within sequences with TSequenceFeatureObservations */
86  {
87  inline TFeatureObservation() { }
88  inline TFeatureObservation(const TLandmarkID _id_feature, const TCameraPoseID _id_frame, const mrpt::utils::TPixelCoordf &_px) : id_feature(_id_feature), id_frame(_id_frame), px(_px) { }
89 
90  TLandmarkID id_feature; //!< A unique ID of this feature
91  TCameraPoseID id_frame; //!< A unique ID of a "frame" (camera position) from where the feature was observed.
92  mrpt::utils::TPixelCoordf px; //!< The pixel coordinates of the observed feature
93  };
94 
95  /** One relative feature observation entry, used with some relative bundle-adjustment functions.
96  */
98  {
99  inline TRelativeFeaturePos() { }
100  inline TRelativeFeaturePos(const mrpt::vision::TCameraPoseID _id_frame_base, const mrpt::math::TPoint3D &_pos) : id_frame_base(_id_frame_base), pos(_pos) { }
101 
102  mrpt::vision::TCameraPoseID id_frame_base; //!< The ID of the camera frame which is the coordinate reference of \a pos
103  mrpt::math::TPoint3D pos; //!< The (x,y,z) location of the feature, wrt to the camera frame \a id_frame_base
104  };
105 
106  /** An index of feature IDs and their relative locations */
107  typedef std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos> TRelativeFeaturePosMap;
108 
109  /** A complete sequence of observations of features from different camera frames (poses).
110  * This structure is the input to some (Bundle-adjustment) methods in mrpt::vision
111  * \note Pixel coordinates can be either "raw" or "undistorted". Read the doc of functions handling this structure to see what they expect.
112  * \sa mrpt::vision::bundle_adj_full
113  */
114  struct VISION_IMPEXP TSequenceFeatureObservations : public std::vector<TFeatureObservation>
115  {
116  typedef std::vector<TFeatureObservation> BASE;
117 
121 
122  /** Saves all entries to a text file, with each line having this format: #FRAME_ID #FEAT_ID #PIXEL_X #PIXEL_Y
123  * The file is self-descripting, since the first line contains a comment line (starting with '%') explaining the format.
124  * Generated files can be loaded from MATLAB.
125  * \sa loadFromTextFile \exception std::exception On I/O error */
126  void saveToTextFile(const std::string &filName, bool skipFirstCommentLine = false) const;
127 
128  /** Load from a text file, in the format described in \a saveToTextFile \exception std::exception On I/O or format error */
129  void loadFromTextFile(const std::string &filName);
130 
131  /** Save the list of observations + the point locations + the camera frame poses to a pair of files in the format
132  * used by the Sparse Bundle Adjustment (SBA) C++ library.
133  *
134  * Point file lines: X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...
135  *
136  * Camera file lines: qr qx qy qz x y z (Pose as a quaternion)
137  * \return false on any error
138  */
139  bool saveAsSBAFiles(
140  const TLandmarkLocationsVec &pts,
141  const std::string &pts_file,
142  const TFramePosesVec &cams,
143  const std::string &cams_file) const;
144 
145 
146  /** Remove all those features that don't have a minimum number of observations from different camera frame IDs.
147  * \return the number of erased entries.
148  * \sa After calling this you may want to call \a compressIDs */
149  size_t removeFewObservedFeatures(size_t minNumObservations = 3);
150 
151  /** Remove all but one out of \a decimate_ratio camera frame IDs from the list (eg: from N camera pose IDs at return there will be just N/decimate_ratio)
152  * The algorithm first builds a sorted list of frame IDs, then keep the lowest ID, remove the next "decimate_ratio-1", and so on.
153  * \sa After calling this you may want to call \a compressIDs */
154  void decimateCameraFrames(const size_t decimate_ratio);
155 
156  /** Rearrange frame and feature IDs such as they start at 0 and there are no gaps.
157  * \param old2new_camIDs If provided, the mapping from old to new IDs is stored here.
158  * \param old2new_lmIDs If provided, the mapping from old to new IDs is stored here. */
159  void compressIDs(
160  std::map<TCameraPoseID,TCameraPoseID> *old2new_camIDs=NULL,
161  std::map<TLandmarkID,TLandmarkID> *old2new_lmIDs=NULL );
162 
163  };
164 
165  /** Parameters associated to a stereo system
166  */
168  {
169  /** Initilization of default parameters */
171 
172  void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string &section) MRPT_OVERRIDE; // See base docs
173  void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE; // See base docs
174 
175  /** Method for propagating the feature's image coordinate uncertainty into 3D space. Default value: Prop_Linear
176  */
178  {
179  /** Linear propagation of the uncertainty
180  */
181  Prop_Linear = -1,
182  /** Uncertainty propagation through the Unscented Transformation
183  */
185  /** Uncertainty propagation through the Scaled Unscented Transformation
186  */
187  Prop_SUT
188  };
189 
191 
192  /** Stereo Fundamental matrix */
194 
195  /** Intrinsic parameters
196  */
198  /** Baseline. Default value: baseline = 0.119f; [Bumblebee]
199  */
200  float baseline;
201  /** Standard deviation of the error in feature detection. Default value: stdPixel = 1
202  */
203  float stdPixel;
204  /** Standard deviation of the error in disparity computation. Default value: stdDisp = 1
205  */
206  float stdDisp;
207  /** Maximum allowed distance. Default value: maxZ = 20.0f
208  */
209  float maxZ;
210  /** Maximum allowed distance. Default value: minZ = 0.5f
211  */
212  float minZ;
213  /** Maximum allowed height. Default value: maxY = 3.0f
214  */
215  float maxY;
216  /** K factor for the UT. Default value: k = 1.5f
217  */
218  float factor_k;
219  /** Alpha factor for SUT. Default value: a = 1e-3
220  */
221  float factor_a;
222  /** Beta factor for the SUT. Default value: b = 2.0f
223  */
224  float factor_b;
225 
226  /** Parameters initialization
227  */
228  //TStereoSystemParams();
229 
230  }; // End struct TStereoSystemParams
231 
232  /** A structure for storing a 3D ROI
233  */
235  {
236  // Constructors
237  TROI();
238  TROI(float x1, float x2, float y1, float y2, float z1, float z2);
239 
240  // Members
241  float xMin;
242  float xMax;
243  float yMin;
244  float yMax;
245  float zMin;
246  float zMax;
247  }; // end struct TROI
248 
249  /** A structure for defining a ROI within an image
250  */
252  {
253  // Constructors
254  TImageROI();
255  TImageROI( float x1, float x2, float y1, float y2 );
256 
257  // Members
258  /** X coordinate limits [0,imageWidth)
259  */
260  float xMin, xMax;
261  /** Y coordinate limits [0,imageHeight)
262  */
263  float yMin, yMax;
264  }; // end struct TImageROI
265 
266  /** A structure containing options for the matching
267  */
269  {
270 
271  /** Method for propagating the feature's image coordinate uncertainty into 3D space. Default value: Prop_Linear
272  */
274  {
275  /** Matching by cross correlation of the image patches
276  */
277  mmCorrelation = 0,
278  /** Matching by Euclidean distance between SIFT descriptors
279  */
281  /** Matching by Euclidean distance between SURF descriptors
282  */
284  /** Matching by sum of absolute differences of the image patches
285  */
287  /** Matching by Hamming distance between ORB descriptors
288  */
289  mmDescriptorORB
290  };
291 
292  // For determining
293  bool useEpipolarRestriction; //!< Whether or not take into account the epipolar restriction for finding correspondences
294  bool hasFundamentalMatrix; //!< Whether or not there is a fundamental matrix
295  bool parallelOpticalAxis; //!< Whether or not the stereo rig has the optical axes parallel
296  bool useXRestriction; //!< Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example)
297  bool addMatches; //!< Whether or not to add the matches found into the input matched list (if false the input list will be cleared before being filled with the new matches)
298  bool useDisparityLimits; //!< Whether or not use limits (min,max) for the disparity, see also 'min_disp, max_disp'
299  bool enable_robust_1to1_match; //!< Whether or not only permit matches that are consistent from left->right and right->left
300 
301  float min_disp, max_disp; //!< Disparity limits, see also 'useDisparityLimits'
302 
304 
305  // General
306  TMatchingMethod matching_method; //!< Matching method
307  float epipolar_TH; //!< Epipolar constraint (rows of pixels)
308 
309  // SIFT
310  float maxEDD_TH; //!< Maximum Euclidean Distance Between SIFT Descriptors
311  float EDD_RATIO; //!< Boundary Ratio between the two lowest EDD
312 
313  // KLT
314  float minCC_TH; //!< Minimum Value of the Cross Correlation
315  float minDCC_TH; //!< Minimum Difference Between the Maximum Cross Correlation Values
316  float rCC_TH; //!< Maximum Ratio Between the two highest CC values
317 
318  // SURF
319  float maxEDSD_TH; //!< Maximum Euclidean Distance Between SURF Descriptors
320  float EDSD_RATIO; //!< Boundary Ratio between the two lowest SURF EDSD
321 
322  // SAD
323  double maxSAD_TH; //!< Minimum Euclidean Distance Between Sum of Absolute Differences
324  double SAD_RATIO; //!< Boundary Ratio between the two highest SAD
325 
326  // ORB
327  double maxORB_dist; //!< Maximun distance between ORB descriptors
328 
329 // // To estimate depth
330  bool estimateDepth; //!< Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now).
331  double maxDepthThreshold; //!< The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered.
332 // double fx,cx,cy,baseline; //!< Intrinsic parameters of the stereo rig
333 
334  /** Constructor */
335  TMatchingOptions( );
336 
337  void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string &section) MRPT_OVERRIDE; // See base docs
338  void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE; // See base docs
339 
340 #define COPY_MEMBER(_m) this->_m = o._m;
341 #define CHECK_MEMBER(_m) this->_m == o._m
342 
343  bool operator==( const TMatchingOptions & o ) const
344  {
345  return
346  CHECK_MEMBER(useXRestriction) &&
347  CHECK_MEMBER(useDisparityLimits) &&
348  CHECK_MEMBER(useEpipolarRestriction) &&
349  CHECK_MEMBER(addMatches) &&
350  CHECK_MEMBER(EDD_RATIO) &&
351  CHECK_MEMBER(EDSD_RATIO) &&
352  CHECK_MEMBER(enable_robust_1to1_match) &&
353  CHECK_MEMBER(epipolar_TH) &&
354  CHECK_MEMBER(estimateDepth) &&
355  CHECK_MEMBER(F) &&
356  CHECK_MEMBER(hasFundamentalMatrix) &&
357  CHECK_MEMBER(matching_method) &&
358  CHECK_MEMBER(maxDepthThreshold) &&
359  CHECK_MEMBER(maxEDD_TH) &&
360  CHECK_MEMBER(maxEDSD_TH) &&
361  CHECK_MEMBER(maxORB_dist) &&
362  CHECK_MEMBER(maxSAD_TH) &&
363  CHECK_MEMBER(max_disp) &&
364  CHECK_MEMBER(minCC_TH) &&
365  CHECK_MEMBER(minDCC_TH) &&
366  CHECK_MEMBER(min_disp) &&
367  CHECK_MEMBER(parallelOpticalAxis) &&
368  CHECK_MEMBER(rCC_TH) &&
369  CHECK_MEMBER(SAD_RATIO);
370  }
371 
372  void operator=( const TMatchingOptions & o )
373  {
374  COPY_MEMBER(useXRestriction)
375  COPY_MEMBER(useDisparityLimits)
376  COPY_MEMBER(useEpipolarRestriction)
377  COPY_MEMBER(addMatches)
378  COPY_MEMBER(EDD_RATIO)
379  COPY_MEMBER(EDSD_RATIO)
380  COPY_MEMBER(enable_robust_1to1_match)
381  COPY_MEMBER(epipolar_TH)
382  COPY_MEMBER(estimateDepth)
383  COPY_MEMBER(F)
384  COPY_MEMBER(hasFundamentalMatrix)
385  COPY_MEMBER(matching_method)
386  COPY_MEMBER(maxDepthThreshold)
387  COPY_MEMBER(maxEDD_TH)
388  COPY_MEMBER(maxEDSD_TH)
389  COPY_MEMBER(maxORB_dist)
390  COPY_MEMBER(maxSAD_TH)
391  COPY_MEMBER(max_disp)
392  COPY_MEMBER(minCC_TH)
393  COPY_MEMBER(minDCC_TH)
394  COPY_MEMBER(min_disp)
395  COPY_MEMBER(parallelOpticalAxis)
396  COPY_MEMBER(rCC_TH)
397  COPY_MEMBER(SAD_RATIO)
398  }
399 
400  }; // end struct TMatchingOptions
401 
402  /** Struct containing the output after matching multi-resolution SIFT-like descriptors
403  */
405  {
406  int nMatches;
407 
408  std::vector<int> firstListCorrespondences; //!< Contains the indexes within the second list corresponding to the first one.
409  std::vector<int> secondListCorrespondences; //!< Contains the indexes within the first list corresponding to the second one.
410  std::vector<int> firstListFoundScales; //!< Contains the scales of the first list where the correspondence was found.
411  std::vector<double> firstListDistance; //!< Contains the distances between the descriptors.
412 
413  TMultiResMatchingOutput() : nMatches(0),
414  firstListCorrespondences(), secondListCorrespondences(),
415  firstListFoundScales(), firstListDistance() {}
416 
417  }; // end struct TMultiResMatchingOutput
418 
419  /** Struct containing the options when matching multi-resolution SIFT-like descriptors
420  */
422  {
423  bool useOriFilter; //!< Whether or not use the filter based on orientation test
424  double oriThreshold; //!< The threshold for the orientation test
425 
426  bool useDepthFilter; //!< Whether or not use the filter based on the depth test
427 
428  double matchingThreshold; //!< The absolute threshold in descriptor distance for considering a match
429  double matchingRatioThreshold; //!< The ratio between the two lowest distances threshold for considering a match
430  uint32_t lowScl1, lowScl2; //!< The lowest scales in the two features to be taken into account in the matching process
431  uint32_t highScl1, highScl2; //!< The highest scales in the two features to be taken into account in the matching process
432 
433  uint32_t searchAreaSize; //!< Size of the squared area where to search for a match.
434  uint32_t lastSeenThreshold; //!< The allowed number of frames since a certain feature was seen for the last time.
435  uint32_t timesSeenThreshold; //!< The minimum number of frames for a certain feature to be considered stable.
436 
437  uint32_t minFeaturesToFind; //!< The minimum number of features allowed in the system. If current number is below this value, more features will be found.
438  uint32_t minFeaturesToBeLost; //!< The minimum number of features allowed in the system to not be considered to be lost.
439 
440  /** Default constructor
441  */
443  useOriFilter( true ), oriThreshold( 0.2 ),
444  useDepthFilter( true ), matchingThreshold( 1e4 ), matchingRatioThreshold( 0.5 ),
445  lowScl1(0), lowScl2(0), highScl1(6), highScl2(6), searchAreaSize(20), lastSeenThreshold(10), timesSeenThreshold(5),
446  minFeaturesToFind(30), minFeaturesToBeLost(5) {}
447 
449  const bool &_useOriFilter, const double &_oriThreshold, const bool &_useDepthFilter,
450  const double &_th, const double &_th2, const unsigned int &_lwscl1, const unsigned int &_lwscl2,
451  const unsigned int &_hwscl1, const unsigned int &_hwscl2, const int &_searchAreaSize, const int &_lsth, const int &_tsth,
452  const int &_minFeaturesToFind, const int &_minFeaturesToBeLost ) :
453  useOriFilter( _useOriFilter ), oriThreshold( _oriThreshold ), useDepthFilter( _useDepthFilter ),
454  matchingThreshold ( _th ), matchingRatioThreshold ( _th2 ), lowScl1( _lwscl1 ), lowScl2( _lwscl2 ),
455  highScl1( _hwscl1 ), highScl2( _hwscl2 ), searchAreaSize( _searchAreaSize ), lastSeenThreshold( _lsth ), timesSeenThreshold( _tsth ),
456  minFeaturesToFind( _minFeaturesToFind ), minFeaturesToBeLost(_minFeaturesToBeLost) {}
457 
458  void loadFromConfigFile( const mrpt::utils::CConfigFileBase &cfg, const std::string &section ) MRPT_OVERRIDE;
459  void saveToConfigFile( mrpt::utils::CConfigFileBase &cfg, const std::string &section ) const MRPT_OVERRIDE;
460  void dumpToTextStream( mrpt::utils::CStream &out) const MRPT_OVERRIDE;
461 
462  }; // end TMultiResDescMatchOptions
463 
464  /** Struct containing the options when computing the multi-resolution SIFT-like descriptors
465  */
467  {
468  uint32_t basePSize; //!< The size of the base patch
469  std::vector<double> scales; //!< The set of scales relatives to the base patch
470  uint32_t comLScl, comHScl; //!< The subset of scales for which to compute the descriptors
471  double sg1, sg2, sg3; //!< The sigmas for the Gaussian kernels
472  bool computeDepth; //!< Whether or not to compute the depth of the feature
473  bool blurImage; //!< Whether or not to blur the image previously to compute the descriptors
474  double fx,cx,cy,baseline; //!< Intrinsic stereo pair parameters for computing the depth of the feature
475  bool computeHashCoeffs; //!< Whether or not compute the coefficients for mantaining a HASH table of descriptors (for relocalization)
476 
477  double cropValue; //!< The SIFT-like descriptor is cropped at this value during normalization
478 
479  /** Default constructor
480  */
482  basePSize(23), sg1 (0.5), sg2(7.5), sg3(8.0), computeDepth(true), blurImage(true), fx(0.0), cx(0.0), cy(0.0), baseline(0.0), computeHashCoeffs(false), cropValue(0.2)
483  {
484  scales.resize(7);
485  scales[0] = 0.5;
486  scales[1] = 0.8;
487  scales[2] = 1.0;
488  scales[3] = 1.2;
489  scales[4] = 1.5;
490  scales[5] = 1.8;
491  scales[6] = 2.0;
492  comLScl = 0;
493  comHScl = 6;
494  }
495 
496  TMultiResDescOptions( const unsigned int &_basePSize, const std::vector<double> &_scales,
497  const unsigned int &_comLScl, const unsigned int &_comHScl,
498  const double &_sg1, const double &_sg2, const double &_sg3,
499  const bool &_computeDepth, const bool _blurImage, const double &_fx, const double &_cx, const double &_cy, const double &_baseline, const bool &_computeHashCoeffs, const double &_cropValue ):
500  basePSize( _basePSize ), comLScl( _comLScl ), comHScl( _comHScl ),
501  sg1( _sg1 ), sg2( _sg2 ), sg3( _sg3 ),
502  computeDepth( _computeDepth ), blurImage( _blurImage ), fx( _fx ), cx( _cx ), cy( _cy ), baseline( _baseline ), computeHashCoeffs( _computeHashCoeffs), cropValue( _cropValue )
503  {
504  scales.resize( _scales.size() );
505  for(unsigned int k = 0; k < _scales.size(); ++k)
506  scales[k] = _scales[k];
507  }
508 
509  void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source,const std::string &section) MRPT_OVERRIDE; // See base docs
510  void saveToConfigFile( mrpt::utils::CConfigFileBase &cfg, const std::string &section ) const MRPT_OVERRIDE; // See base docs
511  void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE; // See base docs
512 
513  }; // end TMultiResDescOptions
514 
515 
516  /** @} */ // end of grouping
517 
518  }
519 }
520 
521 
522 #endif
uint32_t highScl2
The highest scales in the two features to be taken into account in the matching process.
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.
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.
uint32_t minFeaturesToFind
The minimum number of features allowed in the system. If current number is below this value...
void operator=(const TMatchingOptions &o)
double maxORB_dist
Maximun distance between ORB descriptors.
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...
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...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
double SAD_RATIO
Boundary Ratio between the two highest SAD.
Struct containing the output after matching multi-resolution SIFT-like descriptors.
One feature observation entry, used within sequences with TSequenceFeatureObservations.
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
#define CHECK_MEMBER(_m)
TSequenceFeatureObservations(const TSequenceFeatureObservations &o)
void saveToTextFile(const std::string &file, mrpt::math::TMatrixTextFileFormat fileFormat=mrpt::math::MATRIX_FORMAT_ENG, bool appendMRPTHeader=false, const std::string &userHeader=std::string()) const
Save matrix to a text file, compatible with MATLAB text format (see also the methods of matrix classe...
std::vector< int > secondListCorrespondences
Contains the indexes within the first list corresponding to the second one.
float epipolar_TH
Epipolar constraint (rows of pixels)
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.
TFeatureObservation(const TLandmarkID _id_feature, const TCameraPoseID _id_frame, const mrpt::utils::TPixelCoordf &_px)
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 approach to co...
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...
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:38
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.
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.
double sg3
The sigmas for the Gaussian kernels.
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
Uncertainty propagation through the Unscented Transformation.
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. If its computed depth is larger than this, the match won&#39;t be considered.
FASTER-9 detector, Edward Rosten&#39;s libcvd implementation optimized for SSE2.
uint64_t TFeatureID
Definition of a feature ID.
Bit-based feature descriptor.
One relative feature observation entry, used with some relative bundle-adjustment functions...
GLsizei const GLchar ** string
Definition: glext.h:3919
double cropValue
The SIFT-like descriptor is cropped at this value during normalization.
TDescriptorType
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...
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...
void loadFromTextFile(const std::string &file)
Load matrix from a text file, compatible with MATLAB text format.
std::vector< double > scales
The set of scales relatives to the base patch.
unsigned __int64 uint64_t
Definition: rptypes.h:52
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)
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.
bool hasFundamentalMatrix
Whether or not there is a fundamental matrix.
GLsizei GLsizei GLchar * source
Definition: glext.h:3908
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< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
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)
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:3779
bool operator==(const TMatchingOptions &o) const
ORB detector and descriptor, OpenCV&#39;s implementation ("ORB: an efficient alternative to SIFT or SURF"...
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.
mrpt::aligned_containers< TCameraPoseID, mrpt::poses::CPose3D >::map_t TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
bool useOriFilter
Whether or not use the filter based on orientation test.
unsigned __int32 uint32_t
Definition: rptypes.h:49
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)
std::vector< TYPE1, Eigen::aligned_allocator< TYPE1 > > vector_t
double matchingRatioThreshold
The ratio between the two lowest distances threshold for considering a match.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
float stdDisp
Standard deviation of the error in disparity computation.
uint32_t lowScl2
The lowest scales in the two features to be taken into account in the matching process.
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.



Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019