MRPT  1.9.9
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-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 CMetricMap_H
10 #define CMetricMap_H
11 
15 #include <mrpt/math/math_frwds.h>
17 #include <mrpt/obs/CObservation.h>
22 #include <mrpt/obs/obs_frwds.h>
23 #include <deque>
24 
25 namespace mrpt::maps
26 {
27 /** Declares a virtual base class for all metric maps storage classes.
28  * In this class virtual methods are provided to allow the insertion
29  * of any type of "CObservation" objects into the metric map, thus
30  * updating the map (doesn't matter if it is a 2D/3D grid, a point map, etc.).
31  *
32  * Observations don't include any information about the
33  * robot pose, just the raw observation and information about
34  * the sensor pose relative to the robot mobile base coordinates origin.
35  *
36  * Note that all metric maps implement this mrpt::system::CObservable
37  *interface,
38  * emitting the following events:
39  * - mrpt::obs::mrptEventMetricMapClear: Upon call of the ::clear() method.
40  * - mrpt::obs::mrptEventMetricMapInsert: Upon insertion of an observation
41  *that effectively modifies the map (e.g. inserting an image into a grid map
42  *will NOT raise an event, inserting a laser scan will).
43  *
44  * To check what observations are supported by each metric map, see: \ref
45  *maps_observations
46  *
47  * \note All derived class must implement a static class factory
48  *`<metric_map_class>::MapDefinition()` that builds a default
49  *TMetricMapInitializer [New in MRPT 1.3.0]
50  *
51  * \sa CObservation, CSensoryFrame, CMultiMetricMap
52  * \ingroup mrpt_obs_grp
53  */
56 {
58 
59  private:
60  /** Internal method called by clear() */
61  virtual void internal_clear() = 0;
62 
63  /** Internal method called by insertObservation() */
64  virtual bool internal_insertObservation(
65  const mrpt::obs::CObservation* obs,
66  const mrpt::poses::CPose3D* robotPose = NULL) = 0;
67 
68  /** Internal method called by computeObservationLikelihood() */
70  const mrpt::obs::CObservation* obs,
71  const mrpt::poses::CPose3D& takenFrom) = 0;
72  /** Internal method called by canComputeObservationLikelihood() */
74  const mrpt::obs::CObservation* obs) const
75  {
76  MRPT_UNUSED_PARAM(obs);
77  return true; // Unless implemented otherwise, assume we can always
78  // compute the likelihood.
79  }
80 
81  /** Hook for each time a "internal_insertObservation" returns "true"
82  * This is called automatically from insertObservation() when
83  * internal_insertObservation returns true. */
85  { /* Default: do nothing */}
86 
87  public:
88  /** Erase all the contents of the map */
89  void clear();
90 
91  /** Returns true if the map is empty/no observation has been inserted.
92  */
93  virtual bool isEmpty() const = 0;
94 
95  /** Load the map contents from a CSimpleMap object, erasing all previous
96  * content of the map. This is done invoking `insertObservation()` for each
97  * observation at the mean 3D robot pose of each pose-observations pair in
98  * the CSimpleMap object.
99  *
100  * \sa insertObservation, CSimpleMap
101  * \exception std::exception Some internal steps in invoked methods can
102  * raise exceptions on invalid parameters, etc...
103  */
105  const mrpt::maps::CSimpleMap& Map);
106 
107  ///! \overload
109  {
111  }
112 
113  /** Insert the observation information into this map. This method must be
114  * implemented
115  * in derived classes. See: \ref maps_observations
116  * \param obs The observation
117  * \param robotPose The 3D pose of the robot mobile base in the map
118  * reference system, or NULL (default) if you want to use the origin.
119  *
120  * \sa CObservation::insertObservationInto
121  */
122  bool insertObservation(
123  const mrpt::obs::CObservation* obs,
124  const mrpt::poses::CPose3D* robotPose = NULL);
125 
126  /** A wrapper for smart pointers, just calls the non-smart pointer version.
127  * See: \ref maps_observations */
129  const mrpt::obs::CObservation::Ptr& obs,
130  const mrpt::poses::CPose3D* robotPose = NULL);
131 
132  /** Computes the log-likelihood of a given observation given an arbitrary
133  * robot 3D pose. See: \ref maps_observations
134  *
135  * \param takenFrom The robot's pose the observation is supposed to be taken
136  * from.
137  * \param obs The observation.
138  * \return This method returns a log-likelihood.
139  *
140  * \sa Used in particle filter algorithms, see: CMultiMetricMapPDF::update
141  */
143  const mrpt::obs::CObservation* obs,
144  const mrpt::poses::CPose3D& takenFrom);
145 
146  /** \overload */
148  const mrpt::obs::CObservation* obs,
149  const mrpt::poses::CPose2D& takenFrom);
150 
151  /** Returns true if this map is able to compute a sensible likelihood
152  * function for this observation (i.e. an occupancy grid map cannot with an
153  * image). See: \ref maps_observations
154  * \param obs The observation.
155  * \sa computeObservationLikelihood,
156  * genericMapParams.enableObservationLikelihood
157  */
158  virtual bool canComputeObservationLikelihood(
159  const mrpt::obs::CObservation* obs) const;
160 
161  /** \overload */
163  const mrpt::obs::CObservation::Ptr& obs) const;
164 
165  /** Returns the sum of the log-likelihoods of each individual observation
166  * within a mrpt::obs::CSensoryFrame. See: \ref maps_observations
167  *
168  * \param takenFrom The robot's pose the observation is supposed to be taken
169  * from.
170  * \param sf The set of observations in a CSensoryFrame.
171  * \return This method returns a log-likelihood.
172  * \sa canComputeObservationsLikelihood
173  */
175  const mrpt::obs::CSensoryFrame& sf,
176  const mrpt::poses::CPose2D& takenFrom);
177 
178  /** Returns true if this map is able to compute a sensible likelihood
179  * function for this observation (i.e. an occupancy grid map cannot with an
180  * image). See: \ref maps_observations
181  * \param sf The observations.
182  * \sa canComputeObservationLikelihood
183  */
185  const mrpt::obs::CSensoryFrame& sf) const;
186 
187  /** Constructor */
188  CMetricMap();
189 
190  /** Computes the matching between this and another 2D point map, which
191  *includes finding:
192  * - The set of points pairs in each map
193  * - The mean squared distance between corresponding pairs.
194  *
195  * The algorithm is:
196  * - For each point in "otherMap":
197  * - Transform the point according to otherMapPose
198  * - Search with a KD-TREE the closest correspondences in "this"
199  *map.
200  * - Add to the set of candidate matchings, if it passes all the
201  *thresholds in params.
202  *
203  * This method is the most time critical one into ICP-like algorithms.
204  *
205  * \param otherMap [IN] The other map to compute the matching with.
206  * \param otherMapPose [IN] The pose of the other map as seen from
207  *"this".
208  * \param params [IN] Parameters for the determination of
209  *pairings.
210  * \param correspondences [OUT] The detected matchings pairs.
211  * \param extraResults [OUT] Other results.
212  * \sa compute3DMatchingRatio
213  */
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;
220 
221  /** Computes the matchings between this and another 3D points map - method
222  *used in 3D-ICP.
223  * This method finds the set of point pairs in each map.
224  *
225  * The method is the most time critical one into ICP-like algorithms.
226  *
227  * The algorithm is:
228  * - For each point in "otherMap":
229  * - Transform the point according to otherMapPose
230  * - Search with a KD-TREE the closest correspondences in "this"
231  *map.
232  * - Add to the set of candidate matchings, if it passes all the
233  *thresholds in params.
234  *
235  * \param otherMap [IN] The other map to compute the matching with.
236  * \param otherMapPose [IN] The pose of the other map as seen from
237  *"this".
238  * \param params [IN] Parameters for the determination of
239  *pairings.
240  * \param correspondences [OUT] The detected matchings pairs.
241  * \param extraResults [OUT] Other results.
242  * \sa compute3DMatchingRatio
243  */
244  virtual void determineMatching3D(
245  const mrpt::maps::CMetricMap* otherMap,
246  const mrpt::poses::CPose3D& otherMapPose,
247  mrpt::tfest::TMatchingPairList& correspondences,
248  const TMatchingParams& params,
249  TMatchingExtraResults& extraResults) const;
250 
251  /** Computes the ratio in [0,1] of correspondences between "this" and the
252  * "otherMap" map, whose 6D pose relative to "this" is "otherMapPose"
253  * In the case of a multi-metric map, this returns the average between the
254  * maps. This method always return 0 for grid maps.
255  * \param otherMap [IN] The other map to compute the matching with.
256  * \param otherMapPose [IN] The 6D pose of the other map as seen from
257  * "this".
258  * \param params [IN] Matching parameters
259  * \return The matching ratio [0,1]
260  * \sa determineMatching2D
261  */
262  virtual float compute3DMatchingRatio(
263  const mrpt::maps::CMetricMap* otherMap,
264  const mrpt::poses::CPose3D& otherMapPose,
265  const TMatchingRatioParams& params) const;
266 
267  /** This virtual method saves the map to a file "filNamePrefix"+<
268  * some_file_extension >, as an image or in any other applicable way (Notice
269  * that other methods to save the map may be implemented in classes
270  * implementing this virtual interface). */
272  const std::string& filNamePrefix) const = 0;
273 
274  /** Returns a 3D object representing the map.
275  * \sa genericMapParams, TMapGenericParams::enableSaveAs3DObject */
276  virtual void getAs3DObject(
277  mrpt::opengl::CSetOfObjects::Ptr& outObj) const = 0;
278 
279  /** Common params to all maps */
281 
282  /** This method is called at the end of each "prediction-update-map
283  * insertion" cycle within
284  * "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
285  * This method should normally do nothing, but in some cases can be used
286  * to free auxiliary cached variables.
287  */
289  { /* Default implementation: do nothing. */}
290 
291  /** Returns the square distance from the 2D point (x0,y0) to the closest
292  * correspondence in the map. */
294  float x0, float y0) const;
295 
296  /** If the map is a simple points map or it's a multi-metric map that
297  * contains EXACTLY one simple points map, return it.
298  * Otherwise, return NULL
299  */
301  {
302  return NULL;
303  }
305  {
306  return NULL;
307  }
308 
309 }; // End of class def.
310 
311 /** A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):
312  */
313 using TMetricMapList = std::deque<CMetricMap*>;
314 
315 }
316 #endif
317 
318 
void clear()
Erase all the contents of the map.
Definition: CMetricMap.cpp:31
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const =0
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
Parameters for CMetricMap::compute3DMatchingRatio()
virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const =0
Returns a 3D object representing the map.
CMetricMap()
Constructor.
Definition: CMetricMap.cpp:29
void loadFromProbabilisticPosesAndObservations(const mrpt::maps::CSimpleMap &Map)
Load the map contents from a CSimpleMap object, erasing all previous content of the map...
Definition: CMetricMap.cpp:37
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:33
virtual void auxParticleFilterCleanUp()
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
Definition: CMetricMap.h:288
double computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)
Computes the log-likelihood of a given observation given an arbitrary robot 3D pose.
Definition: CMetricMap.cpp:189
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
TMapGenericParams genericMapParams
Common params to all maps.
Definition: CMetricMap.h:280
virtual bool canComputeObservationLikelihood(const mrpt::obs::CObservation *obs) const
Returns true if this map is able to compute a sensible likelihood function for this observation (i...
Definition: CMetricMap.cpp:180
virtual float squareDistanceToClosestCorrespondence(float x0, float y0) const
Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map...
Definition: CMetricMap.cpp:170
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
Computes the matching between this and another 2D point map, which includes finding: ...
Definition: CMetricMap.cpp:127
virtual bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)=0
Internal method called by insertObservation()
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
double computeObservationsLikelihood(const mrpt::obs::CSensoryFrame &sf, const mrpt::poses::CPose2D &takenFrom)
Returns the sum of the log-likelihoods of each individual observation within a mrpt::obs::CSensoryFra...
Definition: CMetricMap.cpp:67
A list of TMatchingPair.
Definition: TMatchingPair.h:81
virtual bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation *obs) const
Internal method called by canComputeObservationLikelihood()
Definition: CMetricMap.h:73
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:52
Inherit from this class for those objects capable of being observed by a CObserver class...
Definition: CObservable.h:31
GLsizei const GLchar ** string
Definition: glext.h:4101
std::deque< CMetricMap * > TMetricMapList
A list of metric maps (used in the mrpt::poses::CPosePDFParticles class):
Definition: CMetricMap.h:313
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom)=0
Internal method called by computeObservationLikelihood()
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
Common params to all maps derived from mrpt::maps::CMetricMap.
bool insertObservationPtr(const mrpt::obs::CObservation::Ptr &obs, const mrpt::poses::CPose3D *robotPose=NULL)
A wrapper for smart pointers, just calls the non-smart pointer version.
Definition: CMetricMap.cpp:109
virtual mrpt::maps::CSimplePointsMap * getAsSimplePointsMap()
Definition: CMetricMap.h:304
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Definition: CSerializable.h:30
virtual void OnPostSuccesfulInsertObs(const mrpt::obs::CObservation *)
Hook for each time a "internal_insertObservation" returns "true" This is called automatically from in...
Definition: CMetricMap.h:84
virtual void internal_clear()=0
Internal method called by clear()
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 ...
Definition: CMetricMap.h:300
Parameters for the determination of matchings between point clouds, etc.
void loadFromSimpleMap(const mrpt::maps::CSimpleMap &Map)
!
Definition: CMetricMap.h:108
virtual bool isEmpty() const =0
Returns true if the map is empty/no observation has been inserted.
GLenum const GLfloat * params
Definition: glext.h:3534
virtual float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const
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.
Definition: CMetricMap.cpp:157
bool insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=NULL)
Insert the observation information into this map.
Definition: CMetricMap.cpp:95
virtual void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams &params, TMatchingExtraResults &extraResults) const
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
Definition: CMetricMap.cpp:142
bool canComputeObservationsLikelihood(const mrpt::obs::CSensoryFrame &sf) const
Returns true if this map is able to compute a sensible likelihood function for this observation (i...
Definition: CMetricMap.cpp:86
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186



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