Main MRPT website > C++ reference for MRPT 1.9.9
CMultiMetricMap.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 CMultiMetricMap_H
10 #define CMultiMetricMap_H
11 
13 #include <mrpt/maps/COctoMap.h>
24 #include <mrpt/maps/CBeaconMap.h>
25 #include <mrpt/maps/CMetricMap.h>
28 #include <mrpt/utils/TEnumType.h>
30 #include <mrpt/obs/obs_frwds.h>
31 
32 namespace mrpt
33 {
34 namespace maps
35 {
36 class TSetOfMetricMapInitializers;
37 
38 /** This class stores any customizable set of metric maps.
39  * The internal metric maps can be accessed directly by the user as smart
40  *pointers with CMultiMetricMap::getMapByIndex() or via `iterator`s.
41  * The utility of this container is to operate on several maps simultaneously:
42  *update them by inserting observations,
43  * evaluate the likelihood of one observation by fusing (multiplying) the
44  *likelihoods over the different maps, etc.
45  *
46  * <b>These kinds of metric maps can be kept inside</b> (list may be
47  *incomplete, refer to classes derived from mrpt::maps::CMetricMap):
48  * - mrpt::maps::CSimplePointsMap: For 2D or 3D range scans, ...
49  * - mrpt::maps::COccupancyGridMap2D: 2D, <b>horizontal</b> laser range
50  *scans, at different altitudes.
51  * - mrpt::maps::COctoMap: For 3D occupancy grids of variable resolution,
52  *with octrees (based on the library `octomap`).
53  * - mrpt::maps::CColouredOctoMap: The same than above, but nodes can store
54  *RGB data appart from occupancy.
55  * - mrpt::maps::CLandmarksMap: For visual landmarks,etc...
56  * - mrpt::maps::CGasConcentrationGridMap2D: For gas concentration maps.
57  * - mrpt::maps::CWirelessPowerGridMap2D: For wifi power maps.
58  * - mrpt::maps::CBeaconMap: For range-only SLAM.
59  * - mrpt::maps::CHeightGridMap2D: For elevation maps of height for each
60  *(x,y) location (Digital elevation model, DEM)
61  * - mrpt::maps::CHeightGridMap2D_MRF: DEMs as Markov Random Field (MRF)
62  * - mrpt::maps::CReflectivityGridMap2D: For maps of "reflectivity" for
63  *each
64  *(x,y) location.
65  * - mrpt::maps::CColouredPointsMap: For point map with color.
66  * - mrpt::maps::CWeightedPointsMap: For point map with weights (capable of
67  *"fusing").
68  *
69  * See CMultiMetricMap::setListOfMaps() for the method for initializing this
70  *class programmatically.
71  * See also TSetOfMetricMapInitializers::loadFromConfigFile for a template of
72  *".ini"-like configuration
73  * file that can be used to define which maps to create and all their
74  *parameters.
75  * Alternatively, the list of maps is public so it can be directly
76  *manipulated/accessed in CMultiMetricMap::maps
77  *
78  * Configuring the list of maps: Alternatives
79  * --------------------------------------------
80  *
81  * **Method #1: Using map definition structures**
82  * \code
83  * mrpt::maps::TSetOfMetricMapInitializers map_inits;
84  * {
85  * mrpt::maps::COccupancyGridMap2D::TMapDefinition def;
86  * def.resolution = 0.05;
87  * def.insertionOpts.maxOccupancyUpdateCertainty = 0.8;
88  * def.insertionOpts.maxDistanceInsertion = 30;
89  * map_inits.push_back(def);
90  * }
91  * {
92  * mrpt::maps::CSimplePointsMap::TMapDefinition def;
93  * map_inits.push_back(def);
94  * }
95  * mrpt::maps::CMultiMetricMap theMap;
96  * theMap.setListOfMaps(map_inits);
97  * \endcode
98  *
99  * **Method #2: Using a configuration file**
100  * See TSetOfMetricMapInitializers::loadFromConfigFile() for details on expected
101  *file format.
102  *
103  * \code
104  * mrpt::utils::CConfigFile cfgFile("file.cfg");
105  * mrpt::maps::TSetOfMetricMapInitializers map_inits;
106  * map_inits.loadFromConfigFile(cfgFile, "MapDefinition");
107  *
108  * mrpt::maps::CMultiMetricMap theMap;
109  * theMap.setListOfMaps(map_inits);
110  * \endcode
111  *
112  * **Method #3: Manual manipulation**
113  *
114  * \code
115  * mrpt::maps::CMultiMetricMap theMap;
116  * {
117  * mrpt::maps::CSimplePointsMap::Ptr ptMap =
118  *mrpt::make_aligned_shared<mrpt::maps::CSimplePointsMap>();
119  * theMap.maps.push_back(ptMap);
120  * }
121  * \endcode
122  *
123  * \note [New in MRPT 1.3.0]: `likelihoodMapSelection`, which selected the map
124  *to be used when
125  * computing the likelihood of an observation, has been removed. Use the
126  *`enableObservationLikelihood`
127  * property of each individual map declaration.
128  *
129  * \note [New in MRPT 1.3.0]: `enableInsertion_{pointsMap,...}` have been also
130  *removed.
131  * Use the `enableObservationInsertion` property of each map declaration.
132  *
133  * \note [New in MRPT 1.3.0]: Plain list of maps is exposed in `maps` member.
134  *Proxies named `m_pointsMaps`,`m_gridMaps`, etc.
135  * are provided for backwards-compatibility and for their utility.
136  *
137  * \note This class belongs to [mrpt-slam] instead of [mrpt-maps] due to the
138  *dependency on map classes in mrpt-vision.
139  * \sa CMetricMap \ingroup mrpt_slam_grp
140  */
142 {
144  protected:
145  /** Deletes all maps and clears the internal lists of maps (with
146  * clear_unique(), so user copies remain alive) */
147  void deleteAllMaps();
148  /** Clear all elements of the map. */
149  void internal_clear() override;
150  // See base class docs
152  const mrpt::obs::CObservation* obs,
153  const mrpt::poses::CPose3D* robotPose = nullptr) override;
154  /** Returns true if any of the inner maps is able to compute a sensible
155  * likelihood function for this observation.
156  * \param obs The observation.
157  * \sa computeObservationLikelihood
158  */
160  const mrpt::obs::CObservation* obs) const override;
161  // See docs in base class
163  const mrpt::obs::CObservation* obs,
164  const mrpt::poses::CPose3D& takenFrom) override;
165 
166  public:
167  /** @name Access to internal list of maps: direct list, iterators, utility
168  methods and proxies
169  @{ */
170  typedef std::deque<mrpt::utils::poly_ptr_ptr<mrpt::maps::CMetricMap::Ptr>>
172 
173  /** The list of MRPT metric maps in this object. Use dynamic_cast or smart
174  * pointer-based downcast to access maps by their actual type.
175  * You can directly manipulate this list. Helper methods to initialize it
176  * are described in the docs of CMultiMetricMap
177  */
179 
182  iterator begin() { return maps.begin(); }
183  const_iterator begin() const { return maps.begin(); }
184  iterator end() { return maps.end(); }
185  const_iterator end() const { return maps.end(); }
186  /** Gets the i-th map \exception std::runtime_error On out-of-bounds */
187  mrpt::maps::CMetricMap::Ptr getMapByIndex(size_t idx) const;
188 
189  /** Returns the i'th observation of a given class (or of a descendant
190  * class), or nullptr if there is no such observation in the array.
191  * Example:
192  * \code
193  * CObservationImage::Ptr obs =
194  * m_SF->getObservationByClass<CObservationImage>();
195  * \endcode
196  * By default (ith=0), the first observation is returned.
197  */
198  template <typename T>
199  typename T::Ptr getMapByClass(const size_t& ith = 0) const
200  {
201  size_t foundCount = 0;
202  const mrpt::utils::TRuntimeClassId* class_ID = &T::GetRuntimeClassIdStatic();
203  for (const_iterator it = begin(); it != end(); ++it)
204  if ((*it)->GetRuntimeClass()->derivedFrom(class_ID))
205  if (foundCount++ == ith)
206  return std::dynamic_pointer_cast<T>(it->get_ptr());
207  return typename T::Ptr(); // Not found: return empty smart pointer
208  }
209 
210  /** Takes a const ref of a STL non-associative container of smart pointers
211  * at construction and exposes an interface
212  * mildly similar to that of another STL container containing only those
213  * elements
214  * in the original container that can be `dynamic_cast`ed to
215  * `SELECTED_CLASS_PTR` */
216  template <class SELECTED_CLASS_PTR, class CONTAINER>
218  {
219  typedef typename SELECTED_CLASS_PTR::element_type* ptr_t;
220  typedef const typename SELECTED_CLASS_PTR::element_type* const_ptr_t;
224  : m_source()
225  {
226  } // m_source init in parent copy ctor
227 
230  {
231  return *this;
232  } // Do nothing, we must keep refs to our own parent
235  : m_source()
236  {
237  } // m_source init in parent copy ctor
240  {
241  return *this;
242  } // Do nothing, we must keep refs to our own parent
243  bool empty() const { return size() == 0; }
244  size_t size() const
245  {
246  size_t cnt = 0;
247  for (typename CONTAINER::const_iterator it = m_source->begin();
248  it != m_source->end(); ++it)
249  if (dynamic_cast<const_ptr_t>(it->get())) cnt++;
250  return cnt;
251  }
252  SELECTED_CLASS_PTR operator[](size_t index) const
253  {
254  size_t cnt = 0;
255  for (typename CONTAINER::const_iterator it = m_source->begin();
256  it != m_source->end(); ++it)
257  if (dynamic_cast<const_ptr_t>(it->get()))
258  if (cnt++ == index)
259  {
260  return std::dynamic_pointer_cast<
261  typename SELECTED_CLASS_PTR::element_type>(
262  it->get_ptr());
263  }
264  throw std::out_of_range("Index is out of range");
265  }
266  template <typename ELEMENT>
267  void push_back(const ELEMENT& element)
268  {
269  m_source->push_back(element);
270  }
271 
272  private:
273  CONTAINER* m_source;
274  }; // end ProxyFilterContainerByClass
275 
276  /** A proxy like ProxyFilterContainerByClass, but it directly appears as if
277  * it was a single smart pointer (empty if no matching object is found in
278  * the container) */
279  template <class SELECTED_CLASS_PTR, class CONTAINER>
281  {
282  typedef typename SELECTED_CLASS_PTR::element_type pointee_t;
283  typedef typename SELECTED_CLASS_PTR::element_type* ptr_t;
284  typedef const typename SELECTED_CLASS_PTR::element_type* const_ptr_t;
288  : m_source()
289  {
290  } // m_source init in parent copy ctor
293  o)
294  {
295  return *this;
296  } // Do nothing, we must keep refs to our own parent
299  : m_source()
300  {
301  } // m_source init in parent copy ctor
304  {
305  return *this;
306  } // Do nothing, we must keep refs to our own parent
307 
308  operator const SELECTED_CLASS_PTR&() const
309  {
311  return m_ret;
312  }
313  explicit operator bool() const
314  {
316  return m_ret ? true : false;
317  }
318  ptr_t get()
319  {
321  return m_ret.get();
322  }
324  {
326  if (m_ret)
327  return m_ret.get();
328  else
329  throw std::runtime_error("Tried to derefer nullptr pointer");
330  }
332  {
334  if (m_ret)
335  return *m_ret.get();
336  else
337  throw std::runtime_error("Tried to derefer nullptr pointer");
338  }
339 
340  private:
341  CONTAINER* m_source;
342  mutable SELECTED_CLASS_PTR m_ret;
343  void internal_update_ref() const
344  {
345  for (typename CONTAINER::const_iterator it = m_source->begin();
346  it != m_source->end(); ++it)
347  {
348  if (dynamic_cast<const_ptr_t>(it->get()))
349  {
350  m_ret = std::dynamic_pointer_cast<pointee_t>(it->get_ptr());
351  return;
352  }
353  }
354  m_ret = SELECTED_CLASS_PTR(); // Not found
355  }
356 
357  }; // end ProxySelectorContainerByClass
358 
359  /** STL-like proxy to access this kind of maps in \ref maps */
360  ProxyFilterContainerByClass<mrpt::maps::CSimplePointsMap::Ptr, TListMaps>
362  /** STL-like proxy to access this kind of maps in \ref maps */
365  /** STL-like proxy to access this kind of maps in \ref maps */
368  /** STL-like proxy to access this kind of maps in \ref maps */
371  /** STL-like proxy to access this kind of maps in \ref maps */
373  TListMaps>
375  /** STL-like proxy to access this kind of maps in \ref maps */
377  TListMaps>
379  /** STL-like proxy to access this kind of maps in \ref maps */
382  /** STL-like proxy to access this kind of maps in \ref maps */
384  TListMaps>
386  /** STL-like proxy to access this kind of maps in \ref maps */
388  TListMaps>
390  /** Proxy that looks like a smart pointer to the first matching object in
391  * \ref maps */
393  TListMaps>
395  /** Proxy that looks like a smart pointer to the first matching object in
396  * \ref maps */
398  TListMaps>
400  /** Proxy that looks like a smart pointer to the first matching object in
401  * \ref maps */
404  /** Proxy that looks like a smart pointer to the first matching object in
405  * \ref maps */
408 
409  /** @} */
410 
411  /** Constructor.
412  * \param initializers One internal map will be created for each entry in
413  * this "TSetOfMetricMapInitializers" struct.
414  * If initializers is nullptr, no internal map will be created.
415  */
417  const mrpt::maps::TSetOfMetricMapInitializers* initializers = nullptr);
418 
421 
424 
425  /** Sets the list of internal map according to the passed list of map
426  * initializers (Current maps' content will be deleted!) */
427  void setListOfMaps(
428  const mrpt::maps::TSetOfMetricMapInitializers* initializers);
429  /** \overload */
431  const mrpt::maps::TSetOfMetricMapInitializers& initializers)
432  {
433  this->setListOfMaps(&initializers);
434  }
435 
436  /** Returns true if all maps returns true to their isEmpty() method, which
437  * is map-dependent. Read the docs of each map class */
438  bool isEmpty() const override;
439 
440  // See docs in base class.
441  virtual void determineMatching2D(
442  const mrpt::maps::CMetricMap* otherMap,
443  const mrpt::poses::CPose2D& otherMapPose,
444  mrpt::utils::TMatchingPairList& correspondences,
446  mrpt::maps::TMatchingExtraResults& extraResults) const override;
447 
448  /** See the definition in the base class: Calls in this class become a call
449  * to every single map in this set. */
451  const mrpt::maps::CMetricMap* otherMap,
452  const mrpt::poses::CPose3D& otherMapPose,
453  const TMatchingRatioParams& params) const override;
454 
455  /** The implementation in this class just calls all the corresponding method
456  * of the contained metric maps */
458  const std::string& filNamePrefix) const override;
459 
460  /** This method is called at the end of each "prediction-update-map
461  * insertion" cycle within
462  * "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
463  * This method should normally do nothing, but in some cases can be used
464  * to free auxiliary cached variables.
465  */
466  void auxParticleFilterCleanUp() override;
467 
468  /** Returns a 3D object representing the map.
469  */
470  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
471 
472  /** If the map is a simple point map or it's a multi-metric map that
473  * contains EXACTLY one simple point map, return it.
474  * Otherwise, return NULL
475  */
477  const override;
479 
480  /** An auxiliary variable that can be used freely by the users (this will be
481  * copied to other maps using the copy constructor, copy operator,
482  * streaming,etc) The default value is 0.
483  */
484  unsigned int m_ID;
485 
486 }; // End of class def.
487 
488 } // End of namespace
489 } // End of namespace
490 
491 #endif
void auxParticleFilterCleanUp() override
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
TListMaps::const_iterator const_iterator
Parameters for CMetricMap::compute3DMatchingRatio()
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &initializers)
void deleteAllMaps()
Deletes all maps and clears the internal lists of maps (with clear_unique(), so user copies remain al...
ProxyFilterContainerByClass< mrpt::maps::COctoMap::Ptr, TListMaps > m_octoMaps
STL-like proxy to access this kind of maps in maps.
T::Ptr getMapByClass(const size_t &ith=0) const
Returns the i&#39;th observation of a given class (or of a descendant class), or nullptr if there is no s...
ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMap::Ptr, TListMaps > m_pointsMaps
STL-like proxy to access this kind of maps in maps.
std::shared_ptr< CGasConcentrationGridMap2D > Ptr
ProxyFilterContainerByClass< mrpt::maps::CGasConcentrationGridMap2D::Ptr, TListMaps > m_gasGridMaps
STL-like proxy to access this kind of maps in maps.
Scalar * iterator
Definition: eigen_plugins.h:26
double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
const Scalar * const_iterator
Definition: eigen_plugins.h:27
Takes a const ref of a STL non-associative container of smart pointers at construction and exposes an...
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
ProxyFilterContainerByClass< mrpt::maps::CWirelessPowerGridMap2D::Ptr, TListMaps > m_wifiGridMaps
STL-like proxy to access this kind of maps in maps.
ProxySelectorContainerByClass< mrpt::maps::CBeaconMap::Ptr, TListMaps > m_beaconMap
Proxy that looks like a smart pointer to the first matching object in maps.
const SELECTED_CLASS_PTR::element_type * const_ptr_t
bool isEmpty() const override
Returns true if all maps returns true to their isEmpty() method, which is map-dependent.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
See the definition in the base class: Calls in this class become a call to every single map in this s...
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
const SELECTED_CLASS_PTR::element_type * const_ptr_t
std::shared_ptr< CMetricMap > Ptr
Definition: CMetricMap.h:58
void internal_clear() override
Clear all elements of the map.
GLuint index
Definition: glext.h:4054
A list of TMatchingPair.
Definition: TMatchingPair.h:93
CMultiMetricMap & operator=(const CMultiMetricMap &o)
bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:32
CMultiMetricMap(const mrpt::maps::TSetOfMetricMapInitializers *initializers=nullptr)
Constructor.
ProxySelectorContainerByClass< mrpt::maps::CLandmarksMap::Ptr, TListMaps > m_landmarksMap
Proxy that looks like a smart pointer to the first matching object in maps.
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2D::Ptr, TListMaps > m_gridMaps
STL-like proxy to access this kind of maps in maps.
ProxyFilterContainerByClass< mrpt::maps::CColouredOctoMap::Ptr, TListMaps > m_colourOctoMaps
STL-like proxy to access this kind of maps in maps.
ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&o)
ProxySelectorContainerByClass(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &)
std::shared_ptr< CColouredPointsMap > Ptr
bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation *obs) const override
Returns true if any of the inner maps is able to compute a sensible likelihood function for this obse...
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::maps::CMetricMap::Ptr getMapByIndex(size_t idx) const
Gets the i-th map.
ProxyFilterContainerByClass(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&)
ProxySelectorContainerByClass< mrpt::maps::CWeightedPointsMap::Ptr, TListMaps > m_weightedPointsMap
Proxy that looks like a smart pointer to the first matching object in maps.
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::shared_ptr< CWirelessPowerGridMap2D > Ptr
ProxySelectorContainerByClass(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&)
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
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple point map or it&#39;s a multi-metric map that contains EXACTLY one simple point ma...
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
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers *initializers)
Sets the list of internal map according to the passed list of map initializers (Current maps&#39; content...
ProxyFilterContainerByClass< mrpt::maps::CReflectivityGridMap2D::Ptr, TListMaps > m_reflectivityMaps
STL-like proxy to access this kind of maps in maps.
ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(const ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &o)
ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&o)
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(const ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &o)
unsigned int m_ID
An auxiliary variable that can be used freely by the users (this will be copied to other maps using t...
std::shared_ptr< CWeightedPointsMap > Ptr
TListMaps maps
The list of MRPT metric maps in this object.
A proxy like ProxyFilterContainerByClass, but it directly appears as if it was a single smart pointer...
ProxyFilterContainerByClass(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &)
A structure that holds runtime class type information.
Definition: CObject.h:31
const_iterator end() const
ProxyFilterContainerByClass< mrpt::maps::CHeightGridMap2D::Ptr, TListMaps > m_heightMaps
STL-like proxy to access this kind of maps in maps.
This class stores any customizable set of metric maps.
ProxyFilterContainerByClass< mrpt::maps::CHeightGridMap2D_MRF::Ptr, TListMaps > m_heightMRFMaps
STL-like proxy to access this kind of maps in maps.
Parameters for the determination of matchings between point clouds, etc.
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const mrpt::maps::TMatchingParams &params, mrpt::maps::TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
std::shared_ptr< CReflectivityGridMap2D > Ptr
GLenum const GLfloat * params
Definition: glext.h:3534
SELECTED_CLASS_PTR operator[](size_t index) const
std::deque< mrpt::utils::poly_ptr_ptr< mrpt::maps::CMetricMap::Ptr > > TListMaps
std::shared_ptr< CHeightGridMap2D_MRF > Ptr
ProxySelectorContainerByClass< mrpt::maps::CColouredPointsMap::Ptr, TListMaps > m_colourPointsMap
Proxy that looks like a smart pointer to the first matching object in maps.
TListMaps::iterator iterator
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
The implementation in this class just calls all the corresponding method of the contained metric maps...
const_iterator begin() const



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