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



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014