Main MRPT website > C++ reference for MRPT 1.9.9
CLandmarksMap.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 #ifndef CLandmarksMap_H
10 #define CLandmarksMap_H
11 
13 #include <mrpt/maps/CMetricMap.h>
14 #include <mrpt/maps/CLandmark.h>
20 #include <mrpt/math/CMatrix.h>
23 #include <mrpt/obs/obs_frwds.h>
24 
25 namespace mrpt
26 {
27 namespace maps
28 {
29 namespace internal
30 {
31 typedef std::vector<CLandmark> TSequenceLandmarks;
32 }
33 
34 /** A class for storing a map of 3D probabilistic landmarks.
35  * <br>
36  * Currently these types of landmarks are defined: (see mrpt::maps::CLandmark)
37  * - For "visual landmarks" from images: features with associated
38  descriptors.
39  * - For laser scanners: each of the range measuremnts, as "occupancy"
40  landmarks.
41  * - For grid maps: "Panoramic descriptor" feature points.
42  * - For range-only localization and SLAM: Beacons. It is also supported
43  the simulation of expected beacon-to-sensor readings, observation
44  likelihood,...
45  * <br>
46  * <b>How to load landmarks from observations:</b><br>
47  * When invoking CLandmarksMap::insertObservation(), the values in
48  CLandmarksMap::insertionOptions will
49  * determinate the kind of landmarks that will be extracted and fused into
50  the map. Supported feature
51  * extraction processes are listed next:
52  *
53  <table>
54  <tr> <td><b>Observation class:</b></td> <td><b>Generated Landmarks:</b></td>
55  <td><b>Comments:</b></td> </tr>
56  <tr> <td>CObservationImage</td> <td>vlSIFT</td> <td>1) A SIFT feature is
57  created for each SIFT detected in the image,
58  <br>2) Correspondences between SIFTs features and existing ones are
59  finded by computeMatchingWith3DLandmarks,
60  <br>3) The corresponding feaures are fused, and the new ones added,
61  with an initial uncertainty according to insertionOptions</td> </tr>
62  <tr> <td>CObservationStereoImages</td> <td>vlSIFT</td> <td> Each image is
63  separately procesed by the method for CObservationImage observations </td>
64  </tr>
65  <tr> <td>CObservationStereoImages</td> <td>vlColor</td> <td> TODO... </td>
66  </tr>
67  <tr> <td>CObservation2DRangeScan</td> <td>glOccupancy</td> <td> A landmark is
68  added for each range in the scan, with its appropiate covariance matrix derived
69  from the jacobians matrixes. </td> </tr>
70  </table>
71  *
72  * \sa CMetricMap
73  * \ingroup mrpt_vision_grp
74  */
76 {
78 
79  private:
80  void internal_clear() override;
82  const mrpt::obs::CObservation* obs,
83  const mrpt::poses::CPose3D* robotPose = nullptr) override;
84 
85  public:
86  /** Computes the (logarithmic) likelihood that a given observation was taken
87  *from a given pose in the world being modeled with this map.
88  *
89  * In the current implementation, this method behaves in a different way
90  *according to the nature of
91  * the observation's class:
92  * - "mrpt::obs::CObservation2DRangeScan": This calls
93  *"computeLikelihood_RSLC_2007".
94  * - "mrpt::obs::CObservationStereoImages": This calls
95  *"computeLikelihood_SIFT_LandmarkMap".
96  * <table>
97  * <tr> <td><b>Observation class:</b></td> <td><b>Generated
98  *Landmarks:</b></td> <td><b>Comments:</b></td> </tr>
99  * <tr> <td>CObservationImage</td> <td>vlSIFT</td> <td>1) A SIFT feature is
100  *created for each SIFT detected in the image,
101  * <br>2) Correspondences between SIFTs features and existing ones
102  *are found by computeMatchingWith3DLandmarks,
103  * <br>3) The corresponding feaures are fused, and the new ones
104  * added,
105  *with an initial uncertainty according to insertionOptions</td> </tr>
106  * <tr> <td>CObservationStereoImages</td> <td>vlSIFT</td> <td> Each image is
107  *separately procesed by the method for CObservationImage observations </td>
108  *</tr>
109  * <tr> <td>CObservationStereoImages</td> <td>vlColor</td> <td> TODO...
110  *</td> </tr>
111  * <tr> <td>CObservation2DRangeScan</td> <td>glOccupancy</td> <td> A
112  *landmark is added for each range in the scan, with its appropiate
113  *covariance matrix derived from the jacobians matrixes. </td> </tr>
114  * </table>
115  *
116  * \param takenFrom The robot's pose the observation is supposed to be taken
117  *from.
118  * \param obs The observation.
119  * \return This method returns a likelihood value > 0.
120  *
121  * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update
122  */
124  const mrpt::obs::CObservation* obs,
125  const mrpt::poses::CPose3D& takenFrom) override;
126 
127  /** The color of landmark ellipsoids in CLandmarksMap::getAs3DObject */
129 
131 
132  /** The list of landmarks: the wrapper class is just for maintaining the
133  * KD-Tree representation
134  */
136  {
137  private:
138  /** The actual list */
140 
141  /** A grid-map with the set of landmarks falling into each cell.
142  * \todo Use the KD-tree instead?
143  */
145 
146  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
147  * \sa getLargestDistanceFromOrigin
148  */
150 
151  /** Auxiliary variables used in "getLargestDistanceFromOrigin"
152  * \sa getLargestDistanceFromOrigin
153  */
155 
156  public:
157  /** Default constructor
158  */
160 
162  inline iterator begin() { return m_landmarks.begin(); };
163  inline iterator end() { return m_landmarks.end(); };
164  void clear();
165  inline size_t size() const { return m_landmarks.size(); };
167  inline const_iterator begin() const { return m_landmarks.begin(); };
168  inline const_iterator end() const { return m_landmarks.end(); };
169  /** The object is copied, thus the original copy passed as a parameter
170  * can be released.
171  */
172  void push_back(const CLandmark& lm);
173  CLandmark* get(unsigned int indx);
174  const CLandmark* get(unsigned int indx) const;
175  void isToBeModified(unsigned int indx);
176  void hasBeenModified(unsigned int indx);
177  void hasBeenModifiedAll();
178  void erase(unsigned int indx);
179 
181  /** Returns the landmark with a given landmrk ID, or nullptr if not
182  * found
183  */
184  const CLandmark* getByID(CLandmark::TLandmarkID ID) const;
185 
186  /** Returns the landmark with a given beacon ID, or nullptr if not found
187  */
188  const CLandmark* getByBeaconID(unsigned int ID) const;
189 
190  /** This method returns the largest distance from the origin to any of
191  * the points, such as a sphere centered at the origin with this radius
192  * cover ALL the points in the map (the results are buffered, such as,
193  * if the map is not modified, the second call will be much faster than
194  * the first one).
195  */
196  float getLargestDistanceFromOrigin() const;
197 
198  } landmarks;
199 
200  /** Constructor
201  */
202  CLandmarksMap();
203 
204  /** Virtual destructor.
205  */
206  virtual ~CLandmarksMap();
207 
208  /**** FAMD ***/
209  /** Map of the Euclidean Distance between the descriptors of two SIFT-based
210  * landmarks
211  */
212  static std::map<std::pair<mrpt::maps::CLandmark::TLandmarkID,
214  double>
217  static bool _maxIDUpdated;
218 
220  /**** END FAMD *****/
221 
222  // See docs in base class
224  const mrpt::maps::CMetricMap* otherMap,
225  const mrpt::poses::CPose3D& otherMapPose,
226  const TMatchingRatioParams& params) const override;
227 
228  /** With this struct options are provided to the observation insertion
229  * process.
230  */
232  {
233  public:
234  /** Initilization of default parameters
235  */
237 
238  void loadFromConfigFile(
240  const std::string& section) override; // See base docs
241  void dumpToTextStream(
242  mrpt::utils::CStream& out) const override; // See base docs
243 
244  /** If set to true (default), the insertion of a CObservationImage in
245  * the map will insert SIFT 3D features.
246  */
248 
249  /** If set to true (default), the insertion of a
250  * CObservationStereoImages in the map will insert SIFT 3D features.
251  */
253 
254  /** If set to true (default), inserting a CObservation2DRangeScan in the
255  * map will generate landmarks for each range.
256  */
258 
259  /** [For SIFT landmarks only] The ratio between the best and second best
260  * descriptor distances to set as correspondence (Default=0.4)
261  */
263 
264  /** [For SIFT landmarks only] The minimum likelihood value of a match to
265  * set as correspondence (Default=0.5)
266  */
268 
269  /****************************************** FAMD
270  * ******************************************/
271  /** [For SIFT landmarks only] The minimum Euclidean Descriptor Distance
272  * value of a match to set as correspondence (Default=200)
273  */
275 
276  /** [For SIFT landmarks only] Method to compute 3D matching (Default = 0
277  * (Our method))
278  * 0: Our method -> Euclidean Distance between Descriptors and 3D
279  * position
280  * 1: Sim, Elinas, Griffin, Little -> Euclidean Distance between
281  * Descriptors
282  */
283  unsigned int SIFTMatching3DMethod;
284 
285  /** [For SIFT landmarks only] Method to compute the likelihood (Default
286  * = 0 (Our method))
287  * 0: Our method -> Euclidean Distance between Descriptors and 3D
288  * position
289  * 1: Sim, Elinas, Griffin, Little -> 3D position
290  */
291  unsigned int SIFTLikelihoodMethod;
292 
293  /****************************************** END FAMD
294  * ******************************************/
295 
296  /** [For SIFT landmarks only] The distance (in meters) of the mean value
297  * of landmarks, for the initial position PDF (Default = 3m)
298  */
300 
301  /** [For SIFT landmarks only] The width (in meters, standard deviation)
302  * of the ellipsoid in the axis perpendicular to the main directiom
303  * (Default = 0.05f)
304  */
306 
307  /** [For SIFT landmarks only] The standard deviation (in pixels) for the
308  * SIFTs detector (This is used for the Jacobbian to project stereo
309  * images to 3D)
310  */
312 
313  /** Number of points to extract in the image
314  */
316 
317  /** Maximum depth of 3D landmarks when loading a landmarks map from a
318  * stereo image observation.
319  */
321 
322  /** Maximum distance (in pixels) from a point to a certain epipolar line
323  * to be considered a potential match.
324  */
326 
327  /** Indicates if the images (as well as the SIFT detected features)
328  * should be shown in a window.
329  */
331 
332  /** Parameters of the SIFT feature detector/descriptors while inserting
333  * images in the landmark map.
334  * \note There exists another \a SIFT_feat_options field in the \a
335  * likelihoodOptions member.
336  * \note All parameters of this field can be loaded from a config
337  * file. See mrpt::vision::CFeatureExtraction::TOptions for the names of
338  * the expected fields.
339  */
341 
343 
344  /** With this struct options are provided to the likelihood computations.
345  */
347  {
348  public:
350 
351  void loadFromConfigFile(
353  const std::string& section) override; // See base docs
354  void dumpToTextStream(
355  mrpt::utils::CStream& out) const override; // See base docs
356 
357  /** @name Parameters for: 2D LIDAR scans
358  * @{ */
359  /** The number of rays from a 2D range scan will be decimated by this
360  * factor (default = 1, no decimation) */
362  /** @} */
363 
364  /** @name Parameters for: images
365  * @{ */
370  /** Considers 1 out of "SIFTs_decimation" visual landmarks in the
371  * observation during the likelihood computation. */
373  /** Parameters of the SIFT feature detector/descriptors while inserting
374  * images in the landmark map.
375  * \note There exists another \a SIFT_feat_options field in the \a
376  * insertionOptions member.
377  * \note All parameters of this field can be loaded from a config
378  * file. See mrpt::vision::CFeatureExtraction::TOptions for the names of
379  * the expected fields. */
381  /** @} */
382 
383  /** @name Parameters for: Range-only observation
384  * @{ */
385  /** The standard deviation used for Beacon ranges likelihood
386  * (default=0.08) [meters] \sa beaconRangesUseObservationStd */
388  /** (Default: false) If true, `beaconRangesStd` is ignored and each
389  * individual `CObservationBeaconRanges::stdError` field is used
390  * instead. */
392  /** @} */
393 
394  /** @name Parameters for: External robot poses observation
395  * @{ */
396  /** The standard deviation used for external robot poses likelihood
397  * (default=0.05) [meters] */
399  /** @} */
400 
401  /** @name Parameters for: GPS readings
402  * @{ */
403 
404  /** This struct store de GPS longitude, latitude (in degrees ) and
405  * altitude (in meters) for the first GPS observation
406  * compose with de sensor position on the robot */
407  struct TGPSOrigin
408  {
409  public:
410  TGPSOrigin();
411  /** degrees */
412  double longitude;
413  /** degrees */
414  double latitude;
415  /** meters */
416  double altitude;
417  /** These 3 params allow rotating and shifting GPS coordinates with
418  * other 2D maps (e.g. gridmaps).
419  * - ang : Map rotation [deg]
420  * - x_shift, y_shift: (x,y) offset [m] */
421  double ang, x_shift, y_shift;
422  /** Minimum number of sats to take into account the data */
423  unsigned int min_sat;
424  } GPSOrigin;
425 
426  /** A constant "sigma" for GPS localization data (in meters) */
427  float GPS_sigma;
428  /** @} */
429 
431 
432  /** This struct stores extra results from invoking insertObservation
433  */
435  {
436  /** The number of SIFT detected in left and right images respectively
437  */
438 
439  unsigned int nSiftL, nSiftR;
440 
442 
443  /** With this struct options are provided to the fusion process.
444  */
446  {
447  /** Initialization
448  */
449  TFuseOptions();
450 
451  /** Required number of times of a landmark to be seen not to be removed,
452  * in "ellapsedTime" seconds.
453  */
454  unsigned int minTimesSeen;
455 
456  /** See "minTimesSeen"
457  */
459 
460  } fuseOptions;
461 
462  /** Save to a text file.
463  * In line "i" there are the (x,y,z) mean values of the i'th landmark +
464  * type of landmark + # times seen + timestamp + RGB/descriptor + ID
465  *
466  * Returns false if any error occured, true elsewere.
467  */
468  bool saveToTextFile(std::string file);
469 
470  /** Save to a MATLAB script which displays 2D error ellipses for the map
471  *(top-view, projection on the XY plane).
472  * \param file The name of the file to save the script to.
473  * \param style The MATLAB-like string for the style of the lines (see
474  *'help plot' in MATLAB for posibilities)
475  * \param stdCount The ellipsoids will be drawn from the center to
476  *"stdCount" times the "standard deviations". (default is 2std = 95%
477  *confidence intervals)
478  *
479  * \return Returns false if any error occured, true elsewere.
480  */
482  std::string file, const char* style = "b", float stdCount = 2.0f);
483 
484  /** Save to a MATLAB script which displays 3D error ellipses for the map.
485  * \param file The name of the file to save the script to.
486  * \param style The MATLAB-like string for the style of the lines (see
487  *'help plot' in MATLAB for posibilities)
488  * \param stdCount The ellipsoids will be drawn from the center to a given
489  *confidence interval in [0,1], e.g. 2 sigmas=0.95 (default is 2std = 0.95
490  *confidence intervals)
491  *
492  * \return Returns false if any error occured, true elsewere.
493  */
495  std::string file, const char* style = "b",
496  float confInterval = 0.95f) const;
497 
498  /** Returns the stored landmarks count.
499  */
500  size_t size() const;
501 
502  /** Computes the (logarithmic) likelihood function for a sensed observation
503  "o" according to "this" map.
504  * This is the implementation of the algorithm reported in the paper:
505  <em>J.L. Blanco, J. Gonzalez, and J.A. Fernandez-Madrigal, "A
506  Consensus-based Approach for Estimating the Observation Likelihood of
507  Accurate Range Sensors", in IEEE International Conference on Robotics and
508  Automation (ICRA), Rome (Italy), Apr 10-14, 2007</em>
509  */
511  const CLandmarksMap* s, const mrpt::poses::CPose2D& sensorPose);
512 
513  /** Loads into this landmarks map the SIFT features extracted from an image
514  * observation (Previous contents of map will be erased)
515  * The robot is assumed to be at the origin of the map.
516  * Some options may be applicable from "insertionOptions"
517  * (insertionOptions.SIFTsLoadDistanceOfTheMean)
518  *
519  * \param feat_options Optionally, you can pass here parameters for
520  * changing the default SIFT detector settings.
521  */
523  const mrpt::obs::CObservationImage& obs,
524  const mrpt::vision::CFeatureExtraction::TOptions& feat_options =
526 
527  /** Loads into this landmarks map the SIFT features extracted from an
528  * observation consisting of a pair of stereo-image (Previous contents of
529  * map will be erased)
530  * The robot is assumed to be at the origin of the map.
531  * Some options may be applicable from "insertionOptions"
532  *
533  * \param feat_options Optionally, you can pass here parameters for
534  * changing the default SIFT detector settings.
535  */
539  const mrpt::vision::CFeatureExtraction::TOptions& feat_options =
541 
542  /** Loads into this landmarks-map a set of occupancy features according to a
543  * 2D range scan (Previous contents of map will be erased)
544  * \param obs The observation
545  * \param robotPose The robot pose in the map (Default = the origin)
546  * Some options may be applicable from "insertionOptions"
547  */
550  const mrpt::poses::CPose3D* robotPose = nullptr,
551  unsigned int downSampleFactor = 1);
552 
553  // See docs in base class
555  const mrpt::maps::CMetricMap* otherMap,
556  const mrpt::poses::CPose2D& otherMapPose,
557  float maxDistForCorrespondence, float maxAngularDistForCorrespondence,
558  const mrpt::poses::CPose2D& angularDistPivotPoint,
559  mrpt::utils::TMatchingPairList& correspondences,
560  float& correspondencesRatio, float* sumSqrDist = nullptr,
561  bool onlyKeepTheClosest = false, bool onlyUniqueRobust = false) const;
562 
563  /** Perform a search for correspondences between "this" and another
564  * lansmarks map:
565  * In this class, the matching is established solely based on the
566  * landmarks' IDs.
567  * \param otherMap [IN] The other map.
568  * \param correspondences [OUT] The matched pairs between maps.
569  * \param correspondencesRatio [OUT] This is NumberOfMatchings /
570  * NumberOfLandmarksInTheAnotherMap
571  * \param otherCorrespondences [OUT] Will be returned with a vector
572  * containing "true" for the indexes of the other map's landmarks with a
573  * correspondence.
574  */
576  const mrpt::maps::CLandmarksMap* otherMap,
577  mrpt::utils::TMatchingPairList& correspondences,
578  float& correspondencesRatio,
579  std::vector<bool>& otherCorrespondences) const;
580 
581  /** Changes the reference system of the map to a given 3D pose.
582  */
584 
585  /** Changes the reference system of the map "otherMap" and save the result
586  * in "this" map.
587  */
589  const mrpt::poses::CPose3D& newOrg,
590  const mrpt::maps::CLandmarksMap* otherMap);
591 
592  /** Fuses the contents of another map with this one, updating "this" object
593  * with the result.
594  * This process involves fusing corresponding landmarks, then adding the
595  * new ones.
596  * \param other The other landmarkmap, whose landmarks will be inserted
597  * into "this"
598  * \param justInsertAllOfThem If set to "true", all the landmarks in
599  * "other" will be inserted into "this" without checking for possible
600  * correspondences (may appear duplicates ones, etc...)
601  */
602  void fuseWith(CLandmarksMap& other, bool justInsertAllOfThem = false);
603 
604  /** Returns the (logarithmic) likelihood of a set of landmarks "map" given
605  * "this" map.
606  * See paper: JJAA 2006
607  */
609  CLandmarksMap* map,
610  mrpt::utils::TMatchingPairList* correspondences = nullptr,
611  std::vector<bool>* otherCorrespondences = nullptr);
612 
613  /** Returns true if the map is empty/no observation has been inserted.
614  */
615  bool isEmpty() const override;
616 
617  /** Simulates a noisy reading toward each of the beacons in the landmarks
618  * map, if any.
619  * \param in_robotPose This robot pose is used to simulate the ranges to
620  * each beacon.
621  * \param in_sensorLocationOnRobot The 3D position of the sensor on the
622  * robot
623  * \param out_Observations The results will be stored here. NOTICE that the
624  * fields
625  * "CObservationBeaconRanges::minSensorDistance","CObservationBeaconRanges::maxSensorDistance"
626  * and "CObservationBeaconRanges::stdError" MUST BE FILLED OUT before
627  * calling this function.
628  * An observation will be generated for each beacon in the map, but notice
629  * that some of them may be missed if out of the sensor maximum range.
630  */
632  const mrpt::poses::CPose3D& in_robotPose,
633  const mrpt::poses::CPoint3D& in_sensorLocationOnRobot,
634  mrpt::obs::CObservationBeaconRanges& out_Observations) const;
635 
636  /** Simulates a noisy bearing-range observation of all the beacons
637  * (landamrks with type glBeacon) in the landmarks map, if any.
638  * \param[in] robotPose The robot pose.
639  * \param[in] sensorLocationOnRobot The 3D position of the sensor on the
640  * robot
641  * \param[out] observations The results will be stored here.
642  * \param[in] sensorDetectsIDs If this is set to false, all the landmarks
643  * will be sensed with INVALID_LANDMARK_ID as ID.
644  * \param[in] stdRange The sigma of the sensor noise in range (meters).
645  * \param[in] stdYaw The sigma of the sensor noise in yaw (radians).
646  * \param[in] stdPitch The sigma of the sensor noise in pitch (radians).
647  * \param[out] real_associations If it's not a nullptr pointer, this will
648  * contain at the return the real indices of the landmarks in the map in the
649  * same order than they appear in out_Observations. Useful when
650  * sensorDetectsIDs=false. Spurious readings are assigned a
651  * std::string::npos (=-1) index.
652  * \param[in] spurious_count_mean The mean number of spurious measurements
653  * (uniformly distributed in range & angle) to generate. The number of
654  * spurious is generated by rounding a random Gaussin number. If both this
655  * mean and the std are zero (the default) no spurious readings are
656  * generated.
657  * \param[in] spurious_count_std Read spurious_count_mean above.
658  *
659  * \note The fields
660  * "CObservationBearingRange::fieldOfView_*","CObservationBearingRange::maxSensorDistance"
661  * and "CObservationBearingRange::minSensorDistance" MUST BE FILLED OUT
662  * before calling this function.
663  * \note At output, the observation will have
664  * CObservationBearingRange::validCovariances set to "false" and the 3
665  * sensor_std_* members correctly set to their values.
666  * An observation will be generated for each beacon in the map, but notice
667  * that some of them may be missed if out of the sensor maximum range or
668  * field of view-
669  */
671  const mrpt::poses::CPose3D& robotPose,
672  const mrpt::poses::CPose3D& sensorLocationOnRobot,
674  bool sensorDetectsIDs = true, const float stdRange = 0.01f,
675  const float stdYaw = mrpt::utils::DEG2RAD(0.1f),
676  const float stdPitch = mrpt::utils::DEG2RAD(0.1f),
677  vector_size_t* real_associations = nullptr,
678  const double spurious_count_mean = 0,
679  const double spurious_count_std = 0) const;
680 
681  /** This virtual method saves the map to a file "filNamePrefix"+<
682  *some_file_extension >, as an image or in any other applicable way (Notice
683  *that other methods to save the map may be implemented in classes
684  *implementing this virtual interface).
685  * In the case of this class, these files are generated:
686  * - "filNamePrefix"+"_3D.m": A script for MATLAB for drawing landmarks
687  *as
688  *3D ellipses.
689  * - "filNamePrefix"+"_3D.3DScene": A 3D scene with a "ground plane
690  *grid"
691  *and the set of ellipsoids in 3D.
692  */
694  const std::string& filNamePrefix) const override;
695 
696  /** Returns a 3D object representing the map.
697  * \sa COLOR_LANDMARKS_IN_3DSCENES
698  */
699  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
700 
701  // See base docs
702  virtual void auxParticleFilterCleanUp() override;
703 
705  typedef std::pair<mrpt::math::TPoint3D, unsigned int> TPairIdBeacon;
706  /** Initial contents of the map, especified by a set of 3D Beacons with
707  * associated IDs */
708  std::deque<TPairIdBeacon> initialBeacons;
709  mrpt::maps::CLandmarksMap::TInsertionOptions insertionOpts;
710  mrpt::maps::CLandmarksMap::TLikelihoodOptions likelihoodOpts;
712 
713 }; // End of class def.
714 
715 } // End of namespace
716 } // End of namespace
717 
718 #endif
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
mrpt::utils::CDynamicGrid< vector_int > * getGrid()
Parameters for CMetricMap::compute3DMatchingRatio()
float SiftEDDThreshold
[For SIFT landmarks only] The minimum Euclidean Descriptor Distance value of a match to set as corres...
Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored.
size_t size() const
Returns the stored landmarks count.
void computeMatchingWith3DLandmarks(const mrpt::maps::CLandmarksMap *otherMap, mrpt::utils::TMatchingPairList &correspondences, float &correspondencesRatio, std::vector< bool > &otherCorrespondences) const
Perform a search for correspondences between "this" and another lansmarks map: In this class...
bool insert_SIFTs_from_stereo_images
If set to true (default), the insertion of a CObservationStereoImages in the map will insert SIFT 3D ...
#define MAP_DEFINITION_END(_CLASS_NAME_, _LINKAGE_)
double DEG2RAD(const double x)
Degrees to radians.
static mrpt::utils::TColorf COLOR_LANDMARKS_IN_3DSCENES
The color of landmark ellipsoids in CLandmarksMap::getAs3DObject.
unsigned int SIFTLikelihoodMethod
[For SIFT landmarks only] Method to compute the likelihood (Default = 0 (Our method)) 0: Our method -...
float beaconRangesStd
The standard deviation used for Beacon ranges likelihood (default=0.08) [meters]. ...
const CLandmark * getByID(CLandmark::TLandmarkID ID) const
Returns the landmark with a given landmrk ID, or nullptr if not found.
float SIFTs_stereo_maxDepth
Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation.
void fuseWith(CLandmarksMap &other, bool justInsertAllOfThem=false)
Fuses the contents of another map with this one, updating "this" object with the result.
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
Scalar * iterator
Definition: eigen_plugins.h:26
With this struct options are provided to the observation insertion process.
struct mrpt::maps::CLandmarksMap::TFuseOptions fuseOptions
std::pair< mrpt::math::TPoint3D, unsigned int > TPairIdBeacon
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
float extRobotPoseStd
The standard deviation used for external robot poses likelihood (default=0.05) [meters].
The set of parameters for all the detectors & descriptor algorithms.
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
Declares a class derived from "CObservation" that represents one (or more) range measurements to labe...
STL namespace.
internal::TSequenceLandmarks::iterator iterator
const Scalar * const_iterator
Definition: eigen_plugins.h:27
This struct store de GPS longitude, latitude (in degrees ) and altitude (in meters) for the first GPS...
GLdouble s
Definition: glext.h:3676
int64_t TLandmarkID
The type for the IDs of landmarks.
Definition: CLandmark.h:41
void simulateBeaconReadings(const mrpt::poses::CPose3D &in_robotPose, const mrpt::poses::CPoint3D &in_sensorLocationOnRobot, mrpt::obs::CObservationBeaconRanges &out_Observations) const
Simulates a noisy reading toward each of the beacons in the landmarks map, if any.
unsigned int nSiftL
The number of SIFT detected in left and right images respectively.
The list of landmarks: the wrapper class is just for maintaining the KD-Tree representation.
With this struct options are provided to the likelihood computations.
const CLandmark * getByBeaconID(unsigned int ID) const
Returns the landmark with a given beacon ID, or nullptr if not found.
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void internal_clear() override
Internal method called by clear()
This class allows loading and storing values and vectors of different types from a configuration text...
bool beaconRangesUseObservationStd
(Default: false) If true, beaconRangesStd is ignored and each individual CObservationBeaconRanges::st...
static mrpt::maps::CLandmark::TLandmarkID _mapMaxID
bool insert_SIFTs_from_monocular_images
If set to true (default), the insertion of a CObservationImage in the map will insert SIFT 3D feature...
mrpt::maps::CLandmark::TLandmarkID getMapMaxID()
float SIFTsLoadDistanceOfTheMean
[For SIFT landmarks only] The distance (in meters) of the mean value of landmarks, for the initial position PDF (Default = 3m)
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
int SIFTs_numberOfKLTKeypoints
Number of points to extract in the image.
int SIFTs_decimation
Considers 1 out of "SIFTs_decimation" visual landmarks in the observation during the likelihood compu...
A class for storing a map of 3D probabilistic landmarks.
Definition: CLandmarksMap.h:75
float getLargestDistanceFromOrigin() const
This method returns the largest distance from the origin to any of the points, such as a sphere cente...
internal::TSequenceLandmarks m_landmarks
The actual list.
void push_back(const CLandmark &lm)
The object is copied, thus the original copy passed as a parameter can be released.
float SIFTs_stdXY
[For SIFT landmarks only] The standard deviation (in pixels) for the SIFTs detector (This is used for...
Scale Invariant Feature Transform [LOWE&#39;04].
A list of TMatchingPair.
Definition: TMatchingPair.h:93
Observation class for either a pair of left+right or left+disparity images from a stereo camera...
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:32
virtual ~CLandmarksMap()
Virtual destructor.
double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Computes the (logarithmic) likelihood that a given observation was taken from a given pose in the wor...
GLsizei const GLchar ** string
Definition: glext.h:4101
A class used to store a 3D point.
Definition: CPoint3D.h:32
void changeCoordinatesReference(const mrpt::poses::CPose3D &newOrg)
Changes the reference system of the map to a given 3D pose.
mrpt::vision::CFeatureExtraction::TOptions SIFT_feat_options
Parameters of the SIFT feature detector/descriptors while inserting images in the landmark map...
mrpt::maps::CLandmarksMap::TInsertionOptions insertionOptions
unsigned int minTimesSeen
Required number of times of a landmark to be seen not to be removed, in "ellapsedTime" seconds...
static std::map< std::pair< mrpt::maps::CLandmark::TLandmarkID, mrpt::maps::CLandmark::TLandmarkID >, double > _mEDD
Map of the Euclidean Distance between the descriptors of two SIFT-based landmarks.
bool saveToTextFile(std::string file)
Save to a text file.
unsigned int rangeScan2D_decimation
The number of rays from a 2D range scan will be decimated by this factor (default = 1...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
The class for storing "landmarks" (visual or laser-scan-extracted features,...)
Definition: CLandmark.h:35
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
float ellapsedTime
See "minTimesSeen".
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:55
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:40
bool PLOT_IMAGES
Indicates if the images (as well as the SIFT detected features) should be shown in a window...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
float SIFTsLoadEllipsoidWidth
[For SIFT landmarks only] The width (in meters, standard deviation) of the ellipsoid in the axis perp...
void loadSiftFeaturesFromStereoImageObservation(const mrpt::obs::CObservationStereoImages &obs, mrpt::maps::CLandmark::TLandmarkID fID, const mrpt::vision::CFeatureExtraction::TOptions &feat_options=mrpt::vision::CFeatureExtraction::TOptions(mrpt::vision::featSIFT))
Loads into this landmarks map the SIFT features extracted from an observation consisting of a pair of...
void simulateRangeBearingReadings(const mrpt::poses::CPose3D &robotPose, const mrpt::poses::CPose3D &sensorLocationOnRobot, mrpt::obs::CObservationBearingRange &observations, bool sensorDetectsIDs=true, const float stdRange=0.01f, const float stdYaw=mrpt::utils::DEG2RAD(0.1f), const float stdPitch=mrpt::utils::DEG2RAD(0.1f), vector_size_t *real_associations=nullptr, const double spurious_count_mean=0, const double spurious_count_std=0) const
Simulates a noisy bearing-range observation of all the beacons (landamrks with type glBeacon) in the ...
This observation represents a number of range-bearing value pairs, each one for a detected landmark...
bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
TInsertionOptions()
Initilization of default parameters.
void loadSiftFeaturesFromImageObservation(const mrpt::obs::CObservationImage &obs, const mrpt::vision::CFeatureExtraction::TOptions &feat_options=mrpt::vision::CFeatureExtraction::TOptions(mrpt::vision::featSIFT))
Loads into this landmarks map the SIFT features extracted from an image observation (Previous content...
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
A RGB color - floats in the range [0,1].
Definition: TColor.h:78
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.
virtual void auxParticleFilterCleanUp() override
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
std::vector< size_t > vector_size_t
Definition: types_simple.h:26
void computeMatchingWith2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, float maxDistForCorrespondence, float maxAngularDistForCorrespondence, const mrpt::poses::CPose2D &angularDistPivotPoint, mrpt::utils::TMatchingPairList &correspondences, float &correspondencesRatio, float *sumSqrDist=nullptr, bool onlyKeepTheClosest=false, bool onlyUniqueRobust=false) const
bool insert_Landmarks_from_range_scans
If set to true (default), inserting a CObservation2DRangeScan in the map will generate landmarks for ...
internal::TSequenceLandmarks::const_iterator const_iterator
double computeLikelihood_RSLC_2007(const CLandmarksMap *s, const mrpt::poses::CPose2D &sensorPose)
Computes the (logarithmic) likelihood function for a sensed observation "o" according to "this" map...
bool saveToMATLABScript2D(std::string file, const char *style="b", float stdCount=2.0f)
Save to a MATLAB script which displays 2D error ellipses for the map (top-view, projection on the XY ...
bool saveToMATLABScript3D(std::string file, const char *style="b", float confInterval=0.95f) const
Save to a MATLAB script which displays 3D error ellipses for the map.
struct mrpt::maps::CLandmarksMap::TLikelihoodOptions::TGPSOrigin GPSOrigin
This struct stores extra results from invoking insertObservation.
float SIFTs_epipolar_TH
Maximum distance (in pixels) from a point to a certain epipolar line to be considered a potential mat...
mrpt::maps::CLandmark landmark_type
float SiftLikelihoodThreshold
[For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0...
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::vision::CFeatureExtraction::TOptions SIFT_feat_options
Parameters of the SIFT feature detector/descriptors while inserting images in the landmark map...
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.
double ang
These 3 params allow rotating and shifting GPS coordinates with other 2D maps (e.g.
GLenum const GLfloat * params
Definition: glext.h:3534
float SiftCorrRatioThreshold
[For SIFT landmarks only] The ratio between the best and second best descriptor distances to set as c...
bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
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.
struct mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks landmarks
void loadOccupancyFeaturesFrom2DRangeScan(const mrpt::obs::CObservation2DRangeScan &obs, const mrpt::poses::CPose3D *robotPose=nullptr, unsigned int downSampleFactor=1)
Loads into this landmarks-map a set of occupancy features according to a 2D range scan (Previous cont...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
unsigned int min_sat
Minimum number of sats to take into account the data.
mrpt::utils::CDynamicGrid< vector_int > m_grid
A grid-map with the set of landmarks falling into each cell.
float GPS_sigma
A constant "sigma" for GPS localization data (in meters)
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.
With this struct options are provided to the fusion process.
struct mrpt::maps::CLandmarksMap::TInsertionResults insertionResults
std::vector< CLandmark > TSequenceLandmarks
Definition: CLandmarksMap.h:31
mrpt::maps::CLandmarksMap::TLikelihoodOptions likelihoodOptions
double computeLikelihood_SIFT_LandmarkMap(CLandmarksMap *map, mrpt::utils::TMatchingPairList *correspondences=nullptr, std::vector< bool > *otherCorrespondences=nullptr)
Returns the (logarithmic) likelihood of a set of landmarks "map" given "this" map.
unsigned int SIFTMatching3DMethod
[For SIFT landmarks only] Method to compute 3D matching (Default = 0 (Our method)) 0: Our method -> E...



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