MRPT  1.9.9
CBeaconMap.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 #ifndef CBeaconMap_H
10 #define CBeaconMap_H
11 
12 #include <mrpt/maps/CMetricMap.h>
13 #include <mrpt/maps/CBeacon.h>
15 #include <mrpt/math/CMatrix.h>
17 #include <mrpt/obs/obs_frwds.h>
18 
19 namespace mrpt::maps
20 {
21 /** A class for storing a map of 3D probabilistic beacons, using a Montecarlo,
22  *Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM).
23  * <br>
24  * The individual beacons are defined as mrpt::maps::CBeacon objects.
25  * <br>
26  * When invoking CBeaconMap::insertObservation(), landmarks will be extracted
27  *and fused into the map.
28  * The only currently supported observation type is
29  *mrpt::obs::CObservationBeaconRanges.
30  * See insertionOptions and likelihoodOptions for parameters used when
31  *creating and fusing beacon landmarks.
32  * <br>
33  * Use "TInsertionOptions::insertAsMonteCarlo" to select between 2 different
34  *behaviors:
35  * - Initial PDF of beacons: MonteCarlo, after convergence, pass to
36  *Gaussians; or
37  * - Initial PDF of beacons: SOG, after convergence, a single Gaussian.
38  *
39  * Refer to the papers: []
40  *
41  * \ingroup mrpt_maps_grp
42  * \sa CMetricMap
43  */
45 {
47 
48  public:
49  using TSequenceBeacons = std::deque<CBeacon>;
52 
53  protected:
54  /** The individual beacons */
56 
57  // See docs in base class
58  virtual void internal_clear() override;
59  virtual bool internal_insertObservation(
60  const mrpt::obs::CObservation* obs,
61  const mrpt::poses::CPose3D* robotPose = nullptr) override;
63  const mrpt::obs::CObservation* obs,
64  const mrpt::poses::CPose3D& takenFrom) override;
65 
66  public:
67  /** Constructor */
68  CBeaconMap();
69 
70  /** Resize the number of SOG modes */
71  void resize(const size_t N);
72 
73  /** Access to individual beacons */
74  const CBeacon& operator[](size_t i) const
75  {
76  ASSERT_(i < m_beacons.size());
77  return m_beacons[i];
78  }
79  /** Access to individual beacons */
80  const CBeacon& get(size_t i) const
81  {
82  ASSERT_(i < m_beacons.size());
83  return m_beacons[i];
84  }
85  /** Access to individual beacons */
86  CBeacon& operator[](size_t i)
87  {
88  ASSERT_(i < m_beacons.size());
89  return m_beacons[i];
90  }
91  /** Access to individual beacons */
92  CBeacon& get(size_t i)
93  {
94  ASSERT_(i < m_beacons.size());
95  return m_beacons[i];
96  }
97 
98  iterator begin() { return m_beacons.begin(); }
99  const_iterator begin() const { return m_beacons.begin(); }
100  iterator end() { return m_beacons.end(); }
101  const_iterator end() const { return m_beacons.end(); }
102  /** Inserts a copy of the given mode into the SOG */
103  void push_back(const CBeacon& m) { m_beacons.push_back(m); }
104  // See docs in base class
106  const mrpt::maps::CMetricMap* otherMap,
107  const mrpt::poses::CPose3D& otherMapPose,
108  const TMatchingRatioParams& params) const override;
109 
110  /** With this struct options are provided to the likelihood computations */
112  {
113  public:
114  void loadFromConfigFile(
116  const std::string& section) override; // See base docs
117  void dumpToTextStream(
118  std::ostream& out) const override; // See base docs
119 
120  /** The standard deviation used for Beacon ranges likelihood
121  * (default=0.08m).
122  */
123  double rangeStd = {0.08};
125 
126  /** This struct contains data for choosing the method by which new beacons
127  * are inserted in the map.
128  */
130  {
131  public:
132  /** Initilization of default parameters */
133  void loadFromConfigFile(
135  const std::string& section) override; // See base docs
136  void dumpToTextStream(
137  std::ostream& out) const override; // See base docs
138 
139  /** Insert a new beacon as a set of montecarlo samples (default=true),
140  * or, if false, as a sum of gaussians (see mrpt::maps::CBeacon).
141  * \sa MC_performResampling
142  */
143  bool insertAsMonteCarlo{true};
144 
145  /** Minimum and maximum elevation angles (in degrees) for inserting new
146  * beacons at the first observation: the default values (both 0), makes
147  * the beacons to be in the same horizontal plane that the sensors, that
148  * is, 2D SLAM - the min/max values are -90/90.
149  */
151 
152  /** Number of particles per meter of range, i.e. per meter of the
153  * "radius of the ring".
154  */
155  unsigned int MC_numSamplesPerMeter{1000};
156 
157  /** The threshold for the maximum std (X,Y,and Z) before colapsing the
158  * particles into a Gaussian PDF (default=0.4).
159  */
160  float MC_maxStdToGauss = {0.4f};
161 
162  /** Threshold for the maximum difference from the maximun (log) weight
163  * in the set of samples for erasing a given sample (default=5).
164  */
166 
167  /** If set to false (default), the samples will be generated the first
168  * time a beacon is observed, and their weights just updated
169  * subsequently - if set to "true", fewer samples will be required since
170  * the particles will be resamples when necessary, and a small "noise"
171  * will be added to avoid depletion.
172  */
173  bool MC_performResampling{false};
174 
175  /** The std.dev. of the Gaussian noise to be added to each sample after
176  * resampling, only if MC_performResampling=true.
177  */
179 
180  /** Threshold for the maximum difference from the maximun (log) weight
181  * in the SOG for erasing a given mode (default=20).
182  */
184 
185  /** A parameter for initializing 2D/3D SOGs
186  */
188 
189  /** Constant used to compute the std. dev. int the tangent direction
190  * when creating the Gaussians.
191  */
194 
195  /** Save to a MATLAB script which displays 3D error ellipses for the map.
196  * \param file The name of the file to save the script to.
197  * \param style The MATLAB-like string for the style of the lines (see
198  *'help plot' in MATLAB for posibilities)
199  * \param stdCount The ellipsoids will be drawn from the center to a given
200  *confidence interval in [0,1], e.g. 2 sigmas=0.95 (default is 2std = 0.95
201  *confidence intervals)
202  *
203  * \return Returns false if any error occured, true elsewere.
204  */
206  const std::string& file, const char* style = "b",
207  float confInterval = 0.95f) const;
208 
209  /** Returns the stored landmarks count.
210  */
211  size_t size() const;
212 
213  // See docs in base class
214  virtual void determineMatching2D(
215  const mrpt::maps::CMetricMap* otherMap,
216  const mrpt::poses::CPose2D& otherMapPose,
217  mrpt::tfest::TMatchingPairList& correspondences,
218  const TMatchingParams& params,
219  TMatchingExtraResults& extraResults) const override;
220 
221  /** Perform a search for correspondences between "this" and another
222  * lansmarks map:
223  * Firsly, the landmarks' descriptor is used to find correspondences, then
224  * inconsistent ones removed by
225  * looking at their 3D poses.
226  * \param otherMap [IN] The other map.
227  * \param correspondences [OUT] The matched pairs between maps.
228  * \param correspondencesRatio [OUT] This is NumberOfMatchings /
229  * NumberOfLandmarksInTheAnotherMap
230  * \param otherCorrespondences [OUT] Will be returned with a vector
231  * containing "true" for the indexes of the other map's landmarks with a
232  * correspondence.
233  */
235  const mrpt::maps::CBeaconMap* otherMap,
236  mrpt::tfest::TMatchingPairList& correspondences,
237  float& correspondencesRatio,
238  std::vector<bool>& otherCorrespondences) const;
239 
240  /** Changes the reference system of the map to a given 3D pose.
241  */
243 
244  /** Changes the reference system of the map "otherMap" and save the result
245  * in "this" map.
246  */
248  const mrpt::poses::CPose3D& newOrg,
249  const mrpt::maps::CBeaconMap* otherMap);
250 
251  /** Returns true if the map is empty/no observation has been inserted.
252  */
253  bool isEmpty() const override;
254 
255  /** Simulates a reading toward each of the beacons in the landmarks map, if
256  * any.
257  * \param in_robotPose This robot pose is used to simulate the ranges to
258  * each beacon.
259  * \param in_sensorLocationOnRobot The 3D position of the sensor on the
260  * robot
261  * \param out_Observations The results will be stored here. NOTICE that the
262  * fields
263  * "CObservationBeaconRanges::minSensorDistance","CObservationBeaconRanges::maxSensorDistance"
264  * and "CObservationBeaconRanges::stdError" MUST BE FILLED OUT before
265  * calling this function.
266  * An observation will be generated for each beacon in the map, but notice
267  * that some of them may be missed if out of the sensor maximum range.
268  */
270  const mrpt::poses::CPose3D& in_robotPose,
271  const mrpt::poses::CPoint3D& in_sensorLocationOnRobot,
272  mrpt::obs::CObservationBeaconRanges& out_Observations) const;
273 
274  /** This virtual method saves the map to a file "filNamePrefix"+<
275  *some_file_extension >, as an image or in any other applicable way (Notice
276  *that other methods to save the map may be implemented in classes
277  *implementing this virtual interface).
278  * In the case of this class, these files are generated:
279  * - "filNamePrefix"+"_3D.m": A script for MATLAB for drawing landmarks
280  *as
281  *3D ellipses.
282  * - "filNamePrefix"+"_3D.3DScene": A 3D scene with a "ground plane
283  *grid"
284  *and the set of ellipsoids in 3D.
285  * - "filNamePrefix"+"_covs.m": A textual representation (see
286  *saveToTextFile)
287  */
289  const std::string& filNamePrefix) const override;
290 
291  /** Save a text file with a row per beacon, containing this 11 elements:
292  * - X Y Z: Mean values
293  * - VX VY VZ: Variances of each dimension (C11, C22, C33)
294  * - DET2D DET3D: Determinant of the 2D and 3D covariance matrixes.
295  * - C12, C13, C23: Cross covariances
296  */
297  void saveToTextFile(const std::string& fil) const;
298 
299  /** Returns a 3D object representing the map. */
300  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
301 
302  /** Returns a pointer to the beacon with the given ID, or nullptr if it does
303  * not exist. */
304  const CBeacon* getBeaconByID(CBeacon::TBeaconID id) const;
305  /** Returns a pointer to the beacon with the given ID, or nullptr if it does
306  * not exist. */
308 
310  /** Observations insertion options */
311  mrpt::maps::CBeaconMap::TInsertionOptions insertionOpts;
312  /** Probabilistic observation likelihood options */
313  mrpt::maps::CBeaconMap::TLikelihoodOptions likelihoodOpts;
315 
316 }; // End of class def.
317 
318 }
319 #endif
320 
321 
bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
Scalar * iterator
Definition: eigen_plugins.h:26
Parameters for CMetricMap::compute3DMatchingRatio()
const_iterator end() const
Definition: CBeaconMap.h:101
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
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.
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
This struct contains data for choosing the method by which new beacons are inserted in the map...
Definition: CBeaconMap.h:129
#define MAP_DEFINITION_START(_CLASS_NAME_)
Add a MAP_DEFINITION_START() ...
With this struct options are provided to the likelihood computations.
Definition: CBeaconMap.h:111
Declares a class derived from "CObservation" that represents one (or more) range measurements to labe...
virtual void internal_clear() override
Internal method called by clear()
Definition: CBeaconMap.cpp:94
bool MC_performResampling
If set to false (default), the samples will be generated the first time a beacon is observed...
Definition: CBeaconMap.h:173
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CBeaconMap.cpp:962
double maxElevation_deg
Minimum and maximum elevation angles (in degrees) for inserting new beacons at the first observation:...
Definition: CBeaconMap.h:150
TSequenceBeacons m_beacons
The individual beacons.
Definition: CBeaconMap.h:55
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:113
This class allows loading and storing values and vectors of different types from a configuration text...
void changeCoordinatesReference(const mrpt::poses::CPose3D &newOrg)
Changes the reference system of the map to a given 3D pose.
Definition: CBeaconMap.cpp:823
int64_t TBeaconID
The type for the IDs of landmarks.
Definition: CBeacon.h:43
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
float SOG_maxDistBetweenGaussians
A parameter for initializing 2D/3D SOGs.
Definition: CBeaconMap.h:187
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: CBeaconMap.cpp:974
CBeaconMap()
Constructor.
Definition: CBeaconMap.cpp:87
A list of TMatchingPair.
Definition: TMatchingPair.h:81
A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM).
Definition: CBeaconMap.h:44
float SOG_separationConstant
Constant used to compute the std.
Definition: CBeaconMap.h:192
void saveToTextFile(const std::string &fil) const
Save a text file with a row per beacon, containing this 11 elements:
void push_back(const CBeacon &m)
Inserts a copy of the given mode into the SOG.
Definition: CBeaconMap.h:103
GLsizei const GLchar ** string
Definition: glext.h:4101
A class used to store a 3D point.
Definition: CPoint3D.h:31
CBeacon & operator[](size_t i)
Access to individual beacons.
Definition: CBeaconMap.h:86
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
const CBeacon & operator[](size_t i) const
Access to individual beacons.
Definition: CBeaconMap.h:74
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
Definition: CBeaconMap.cpp:792
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
Initilization of default parameters.
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:54
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:38
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:86
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
double rangeStd
The standard deviation used for Beacon ranges likelihood (default=0.08m).
Definition: CBeaconMap.h:123
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
Definition: CBeaconMap.cpp:980
bool insertAsMonteCarlo
Insert a new beacon as a set of montecarlo samples (default=true), or, if false, as a sum of gaussian...
Definition: CBeaconMap.h:143
const CBeacon * getBeaconByID(CBeacon::TBeaconID id) const
Returns a pointer to the beacon with the given ID, or nullptr if it does not exist.
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
virtual bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
Definition: CBeaconMap.cpp:354
void resize(const size_t N)
Resize the number of SOG modes.
Definition: CBeaconMap.cpp:102
mrpt::maps::CBeaconMap::TLikelihoodOptions likelihoodOptions
std::deque< CBeacon >::const_iterator const_iterator
Definition: CBeaconMap.h:51
double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
Definition: CBeaconMap.cpp:145
const_iterator begin() const
Definition: CBeaconMap.h:99
bool saveToMATLABScript3D(const 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.
Definition: CBeaconMap.cpp:922
unsigned int MC_numSamplesPerMeter
Number of particles per meter of range, i.e.
Definition: CBeaconMap.h:155
std::deque< CBeacon > TSequenceBeacons
Definition: CBeaconMap.h:49
double MC_thresholdNegligible
Threshold for the maximum difference from the maximun (log) weight in the set of samples for erasing ...
Definition: CBeaconMap.h:165
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
mrpt::maps::CBeaconMap::TInsertionOptions insertionOptions
float MC_maxStdToGauss
The threshold for the maximum std (X,Y,and Z) before colapsing the particles into a Gaussian PDF (def...
Definition: CBeaconMap.h:160
Parameters for the determination of matchings between point clouds, etc.
#define MAP_DEFINITION_END(_CLASS_NAME_)
void simulateBeaconReadings(const mrpt::poses::CPose3D &in_robotPose, const mrpt::poses::CPoint3D &in_sensorLocationOnRobot, mrpt::obs::CObservationBeaconRanges &out_Observations) const
Simulates a reading toward each of the beacons in the landmarks map, if any.
GLenum const GLfloat * params
Definition: glext.h:3534
const Scalar * const_iterator
Definition: eigen_plugins.h:27
The class for storing individual "beacon landmarks" under a variety of 3D position PDF distributions...
Definition: CBeacon.h:36
float SOG_thresholdNegligible
Threshold for the maximum difference from the maximun (log) weight in the SOG for erasing a given mod...
Definition: CBeaconMap.h:183
std::deque< CBeacon >::iterator iterator
Definition: CBeaconMap.h:50
size_t size() const
Returns the stored landmarks count.
Definition: CBeaconMap.cpp:98
void computeMatchingWith3DLandmarks(const mrpt::maps::CBeaconMap *otherMap, mrpt::tfest::TMatchingPairList &correspondences, float &correspondencesRatio, std::vector< bool > &otherCorrespondences) const
Perform a search for correspondences between "this" and another lansmarks map: Firsly, the landmarks&#39; descriptor is used to find correspondences, then inconsistent ones removed by looking at their 3D poses.
Definition: CBeaconMap.cpp:845



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020