Main MRPT website > C++ reference for MRPT 1.3.2
maps/CMetricMap.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-2015, 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 CMetricMap_H
10 #define CMetricMap_H
11 
14 #include <mrpt/utils/CObservable.h>
15 #include <mrpt/math/math_frwds.h>
21 #include <mrpt/obs/obs_frwds.h>
22 #include <mrpt/obs/link_pragmas.h>
23 #include <deque>
24 
25 namespace mrpt
26 {
27  namespace maps
28  {
30 
31  /** Declares a virtual base class for all metric maps storage classes.
32  * In this class virtual methods are provided to allow the insertion
33  * of any type of "CObservation" objects into the metric map, thus
34  * updating the map (doesn't matter if it is a 2D/3D grid, a point map, etc.).
35  *
36  * Observations don't include any information about the
37  * robot pose, just the raw observation and information about
38  * the sensor pose relative to the robot mobile base coordinates origin.
39  *
40  * Note that all metric maps implement this mrpt::utils::CObservable interface,
41  * emitting the following events:
42  * - mrpt::obs::mrptEventMetricMapClear: Upon call of the ::clear() method.
43  * - mrpt::obs::mrptEventMetricMapInsert: Upon insertion of an observation that effectively modifies the map (e.g. inserting an image into a grid map will NOT raise an event, inserting a laser scan will).
44  *
45  * \note All derived class must implement a static class factory `<metric_map_class>::MapDefinition()` that builds a default TMetricMapInitializer [New in MRPT 1.3.0]
46  *
47  * \sa CObservation, CSensoryFrame, CMultiMetricMap
48  * \ingroup mrpt_obs_grp
49  */
51  public mrpt::utils::CSerializable,
52  public mrpt::utils::CObservable
53  {
54  // This must be added to any CSerializable derived class:
56 
57  private:
58  /** Internal method called by clear() */
59  virtual void internal_clear() = 0;
60 
61  /** Internal method called by insertObservation() */
62  virtual bool internal_insertObservation(
63  const mrpt::obs::CObservation *obs,
64  const mrpt::poses::CPose3D *robotPose = NULL ) = 0;
65 
66  /** Internal method called by computeObservationLikelihood() */
67  virtual double internal_computeObservationLikelihood( const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom ) = 0;
68  /** Internal method called by canComputeObservationLikelihood() */
69  virtual bool internal_canComputeObservationLikelihood( const mrpt::obs::CObservation *obs )
70  {
71  MRPT_UNUSED_PARAM(obs);
72  return true; // Unless implemented otherwise, assume we can always compute the likelihood.
73  }
74 
75  /** Hook for each time a "internal_insertObservation" returns "true"
76  * This is called automatically from insertObservation() when internal_insertObservation returns true. */
77  virtual void OnPostSuccesfulInsertObs(const mrpt::obs::CObservation *) { /* Default: do nothing */ }
78 
79  public:
80  /** Erase all the contents of the map */
81  void clear();
82 
83  /** Returns true if the map is empty/no observation has been inserted.
84  */
85  virtual bool isEmpty() const = 0;
86 
87  /** Load the map contents from a CSimpleMap object, erasing all previous content of the map.
88  * This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as
89  * given by the "poses::CPosePDF" in the CSimpleMap object.
90  *
91  * \sa insertObservation, CSimpleMap
92  * \exception std::exception Some internal steps in invoked methods can raise exceptions on invalid parameters, etc...
93  */
94  void loadFromProbabilisticPosesAndObservations( const mrpt::maps::CSimpleMap &Map );
95 
96  /** Load the map contents from a CSimpleMap object, erasing all previous content of the map.
97  * This is automaticed invoking "insertObservation" for each observation at the mean 3D robot pose as
98  * given by the "poses::CPosePDF" in the CSimpleMap object.
99  *
100  * \sa insertObservation, CSimpleMap
101  * \exception std::exception Some internal steps in invoked methods can raise exceptions on invalid parameters, etc...
102  */
103  inline void loadFromSimpleMap( const mrpt::maps::CSimpleMap &Map ) { loadFromProbabilisticPosesAndObservations(Map); }
104 
105  /** Insert the observation information into this map. This method must be implemented
106  * in derived classes.
107  * \param obs The observation
108  * \param robotPose The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use the origin.
109  *
110  * \sa CObservation::insertObservationInto
111  */
112  bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose = NULL );
113 
114  /** A wrapper for smart pointers, just calls the non-smart pointer version. */
115  bool insertObservationPtr(const mrpt::obs::CObservationPtr &obs, const mrpt::poses::CPose3D *robotPose = NULL );
116 
117  /** Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
118  *
119  * \param takenFrom The robot's pose the observation is supposed to be taken from.
120  * \param obs The observation.
121  * \return This method returns a log-likelihood.
122  *
123  * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update
124  */
125  double computeObservationLikelihood( const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom );
126 
127  /** \overload */
128  double computeObservationLikelihood( const mrpt::obs::CObservation *obs, const mrpt::poses::CPose2D &takenFrom );
129 
130  /** Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image).
131  * \param obs The observation.
132  * \sa computeObservationLikelihood, genericMapParams.enableObservationLikelihood
133  */
134  virtual bool canComputeObservationLikelihood( const mrpt::obs::CObservation *obs );
135 
136  /** \overload */
137  bool canComputeObservationLikelihood( const mrpt::obs::CObservationPtr &obs );
138 
139  /** Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFrame.
140  *
141  * \param takenFrom The robot's pose the observation is supposed to be taken from.
142  * \param sf The set of observations in a CSensoryFrame.
143  * \return This method returns a log-likelihood.
144  * \sa canComputeObservationsLikelihood
145  */
146  double computeObservationsLikelihood( const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose2D &takenFrom );
147 
148  /** Returns true if this map is able to compute a sensible likelihood function for this observation (i.e. an occupancy grid map cannot with an image).
149  * \param sf The observations.
150  * \sa canComputeObservationLikelihood
151  */
152  bool canComputeObservationsLikelihood( const mrpt::obs::CSensoryFrame &sf );
153 
154  /** Constructor */
155  CMetricMap();
156 
157  /** Destructor */
158  virtual ~CMetricMap();
159 
160  /** Computes the matching between this and another 2D point map, which includes finding:
161  * - The set of points pairs in each map
162  * - The mean squared distance between corresponding pairs.
163  *
164  * The algorithm is:
165  * - For each point in "otherMap":
166  * - Transform the point according to otherMapPose
167  * - Search with a KD-TREE the closest correspondences in "this" map.
168  * - Add to the set of candidate matchings, if it passes all the thresholds in params.
169  *
170  * This method is the most time critical one into ICP-like algorithms.
171  *
172  * \param otherMap [IN] The other map to compute the matching with.
173  * \param otherMapPose [IN] The pose of the other map as seen from "this".
174  * \param params [IN] Parameters for the determination of pairings.
175  * \param correspondences [OUT] The detected matchings pairs.
176  * \param extraResults [OUT] Other results.
177  * \sa compute3DMatchingRatio
178  */
179  virtual void determineMatching2D(
180  const mrpt::maps::CMetricMap * otherMap,
181  const mrpt::poses::CPose2D & otherMapPose,
182  mrpt::utils::TMatchingPairList & correspondences,
183  const TMatchingParams & params,
184  TMatchingExtraResults & extraResults ) const;
185 
186  /** Computes the matchings between this and another 3D points map - method used in 3D-ICP.
187  * This method finds the set of point pairs in each map.
188  *
189  * The method is the most time critical one into ICP-like algorithms.
190  *
191  * The algorithm is:
192  * - For each point in "otherMap":
193  * - Transform the point according to otherMapPose
194  * - Search with a KD-TREE the closest correspondences in "this" map.
195  * - Add to the set of candidate matchings, if it passes all the thresholds in params.
196  *
197  * \param otherMap [IN] The other map to compute the matching with.
198  * \param otherMapPose [IN] The pose of the other map as seen from "this".
199  * \param params [IN] Parameters for the determination of pairings.
200  * \param correspondences [OUT] The detected matchings pairs.
201  * \param extraResults [OUT] Other results.
202  * \sa compute3DMatchingRatio
203  */
204  virtual void determineMatching3D(
205  const mrpt::maps::CMetricMap * otherMap,
206  const mrpt::poses::CPose3D & otherMapPose,
207  mrpt::utils::TMatchingPairList & correspondences,
208  const TMatchingParams & params,
209  TMatchingExtraResults & extraResults ) const;
210 
211  /** Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose"
212  * In the case of a multi-metric map, this returns the average between the maps. This method always return 0 for grid maps.
213  * \param otherMap [IN] The other map to compute the matching with.
214  * \param otherMapPose [IN] The 6D pose of the other map as seen from "this".
215  * \param maxDistForCorr [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence.
216  * \param maxMahaDistForCorr [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence.
217  *
218  * \return The matching ratio [0,1]
219  * \sa determineMatching2D
220  */
221  virtual float compute3DMatchingRatio(
222  const mrpt::maps::CMetricMap *otherMap,
223  const mrpt::poses::CPose3D &otherMapPose,
224  float maxDistForCorr = 0.10f,
225  float maxMahaDistForCorr = 2.0f
226  ) const;
227 
228  /** 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). */
229  virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const = 0;
230 
231  /** Returns a 3D object representing the map.
232  * \sa genericMapParams, TMapGenericParams::enableSaveAs3DObject */
233  virtual void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj ) const = 0;
234 
235  TMapGenericParams genericMapParams; //!< Common params to all maps
236 
237  /** This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
238  * This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.
239  */
240  virtual void auxParticleFilterCleanUp() { /* Default implementation: do nothing. */ }
241 
242  /** Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map. */
243  virtual float squareDistanceToClosestCorrespondence(float x0,float y0 ) const;
244 
245  /** If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points map, return it.
246  * Otherwise, return NULL
247  */
248  virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const { return NULL; }
250 
251  }; // End of class def.
253 
254  /** A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):
255  */
256  typedef std::deque<CMetricMap*> TMetricMapList;
257 
258  } // End of namespace
259 } // End of namespace
260 
261 #endif
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:39
virtual void auxParticleFilterCleanUp()
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
STL namespace.
TMapGenericParams genericMapParams
Common params to all maps.
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
#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...
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
class BASE_IMPEXP CSerializable
Definition: CStream.h:23
A list of TMatchingPair.
Definition: TMatchingPair.h:66
std::deque< CMetricMap * > TMetricMapList
A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Declares a virtual base class for all metric maps storage classes.
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:72
Declares a class that represents any robot&#39;s observation.
Common params to all maps derived from mrpt::maps::CMetricMap.
virtual mrpt::maps::CSimplePointsMap * getAsSimplePointsMap()
virtual void OnPostSuccesfulInsertObs(const mrpt::obs::CObservation *)
Hook for each time a "internal_insertObservation" returns "true" This is called automatically from in...
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const
If the map is a simple points map or it&#39;s a multi-metric map that contains EXACTLY one simple points ...
Parameters for the determination of matchings between point clouds, etc.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
void loadFromSimpleMap(const mrpt::maps::CSimpleMap &Map)
Load the map contents from a CSimpleMap object, erasing all previous content of the map...



Page generated by Doxygen 1.8.12 for MRPT 1.3.2 SVN: at Mon Oct 3 19:22:36 UTC 2016