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



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST