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-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 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>
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::config::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  using TListMaps = std::deque<
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::rtti::TRuntimeClassId* class_ID =
203  &T::GetRuntimeClassIdStatic();
204  for (const_iterator it = begin(); it != end(); ++it)
205  if ((*it)->GetRuntimeClass()->derivedFrom(class_ID))
206  if (foundCount++ == ith)
207  return std::dynamic_pointer_cast<T>(it->get_ptr());
208  return typename T::Ptr(); // Not found: return empty smart pointer
209  }
210 
211  /** Takes a const ref of a STL non-associative container of smart pointers
212  * at construction and exposes an interface
213  * mildly similar to that of another STL container containing only those
214  * elements
215  * in the original container that can be `dynamic_cast`ed to
216  * `SELECTED_CLASS_PTR` */
217  template <class SELECTED_CLASS_PTR, class CONTAINER>
219  {
220  using ptr_t = typename SELECTED_CLASS_PTR::element_type*;
221  using const_ptr_t = const typename SELECTED_CLASS_PTR::element_type*;
225  : m_source()
226  {
227  } // m_source init in parent copy ctor
228 
231  {
232  return *this;
233  } // Do nothing, we must keep refs to our own parent
236  : m_source()
237  {
238  } // m_source init in parent copy ctor
241  {
242  return *this;
243  } // Do nothing, we must keep refs to our own parent
244  bool empty() const { return size() == 0; }
245  size_t size() const
246  {
247  size_t cnt = 0;
248  for (typename CONTAINER::const_iterator it = m_source->begin();
249  it != m_source->end(); ++it)
250  if (dynamic_cast<const_ptr_t>(it->get())) cnt++;
251  return cnt;
252  }
253  SELECTED_CLASS_PTR operator[](size_t index) const
254  {
255  size_t cnt = 0;
256  for (typename CONTAINER::const_iterator it = m_source->begin();
257  it != m_source->end(); ++it)
258  if (dynamic_cast<const_ptr_t>(it->get()))
259  if (cnt++ == index)
260  {
261  return std::dynamic_pointer_cast<
262  typename SELECTED_CLASS_PTR::element_type>(
263  it->get_ptr());
264  }
265  throw std::out_of_range("Index is out of range");
266  }
267  template <typename ELEMENT>
268  void push_back(const ELEMENT& element)
269  {
270  m_source->push_back(element);
271  }
272 
273  private:
274  CONTAINER* m_source;
275  }; // end ProxyFilterContainerByClass
276 
277  /** A proxy like ProxyFilterContainerByClass, but it directly appears as if
278  * it was a single smart pointer (empty if no matching object is found in
279  * the container) */
280  template <class SELECTED_CLASS_PTR, class CONTAINER>
282  {
283  using pointee_t = typename SELECTED_CLASS_PTR::element_type;
284  using ptr_t = typename SELECTED_CLASS_PTR::element_type*;
285  using const_ptr_t = const typename SELECTED_CLASS_PTR::element_type*;
289  : m_source()
290  {
291  } // m_source init in parent copy ctor
294  o)
295  {
296  return *this;
297  } // Do nothing, we must keep refs to our own parent
300  : m_source()
301  {
302  } // m_source init in parent copy ctor
305  {
306  return *this;
307  } // Do nothing, we must keep refs to our own parent
308 
309  operator const SELECTED_CLASS_PTR&() const
310  {
312  return m_ret;
313  }
314  explicit operator bool() const
315  {
317  return m_ret ? true : false;
318  }
320  {
322  return m_ret.get();
323  }
325  {
327  if (m_ret)
328  return m_ret.get();
329  else
330  throw std::runtime_error("Tried to derefer nullptr pointer");
331  }
333  {
335  if (m_ret)
336  return *m_ret.get();
337  else
338  throw std::runtime_error("Tried to derefer nullptr pointer");
339  }
340 
341  private:
342  CONTAINER* m_source;
343  mutable SELECTED_CLASS_PTR m_ret;
344  void internal_update_ref() const
345  {
346  for (typename CONTAINER::const_iterator it = m_source->begin();
347  it != m_source->end(); ++it)
348  {
349  if (dynamic_cast<const_ptr_t>(it->get()))
350  {
351  m_ret = std::dynamic_pointer_cast<pointee_t>(it->get_ptr());
352  return;
353  }
354  }
355  m_ret = SELECTED_CLASS_PTR(); // Not found
356  }
357 
358  }; // end ProxySelectorContainerByClass
359 
360  /** STL-like proxy to access this kind of maps in \ref maps */
361  ProxyFilterContainerByClass<mrpt::maps::CSimplePointsMap::Ptr, TListMaps>
363  /** STL-like proxy to access this kind of maps in \ref maps */
366  /** STL-like proxy to access this kind of maps in \ref maps */
369  /** STL-like proxy to access this kind of maps in \ref maps */
372  /** STL-like proxy to access this kind of maps in \ref maps */
376  /** STL-like proxy to access this kind of maps in \ref maps */
380  /** STL-like proxy to access this kind of maps in \ref maps */
383  /** STL-like proxy to access this kind of maps in \ref maps */
387  /** STL-like proxy to access this kind of maps in \ref maps */
391  /** Proxy that looks like a smart pointer to the first matching object in
392  * \ref maps */
396  /** Proxy that looks like a smart pointer to the first matching object in
397  * \ref maps */
401  /** Proxy that looks like a smart pointer to the first matching object in
402  * \ref maps */
405  /** Proxy that looks like a smart pointer to the first matching object in
406  * \ref maps */
409 
410  /** @} */
411 
412  /** Constructor.
413  * \param initializers One internal map will be created for each entry in
414  * this "TSetOfMetricMapInitializers" struct.
415  * If initializers is nullptr, no internal map will be created.
416  */
418  const mrpt::maps::TSetOfMetricMapInitializers* initializers = nullptr);
419 
422 
425 
426  /** Sets the list of internal map according to the passed list of map
427  * initializers (Current maps' content will be deleted!) */
428  void setListOfMaps(
429  const mrpt::maps::TSetOfMetricMapInitializers* initializers);
430  /** \overload */
432  const mrpt::maps::TSetOfMetricMapInitializers& initializers)
433  {
434  this->setListOfMaps(&initializers);
435  }
436 
437  /** Returns true if all maps returns true to their isEmpty() method, which
438  * is map-dependent. Read the docs of each map class */
439  bool isEmpty() const override;
440 
441  // See docs in base class.
442  virtual void determineMatching2D(
443  const mrpt::maps::CMetricMap* otherMap,
444  const mrpt::poses::CPose2D& otherMapPose,
445  mrpt::tfest::TMatchingPairList& correspondences,
447  mrpt::maps::TMatchingExtraResults& extraResults) const override;
448 
449  /** See the definition in the base class: Calls in this class become a call
450  * to every single map in this set. */
452  const mrpt::maps::CMetricMap* otherMap,
453  const mrpt::poses::CPose3D& otherMapPose,
454  const TMatchingRatioParams& params) const override;
455 
456  /** The implementation in this class just calls all the corresponding method
457  * of the contained metric maps */
459  const std::string& filNamePrefix) const override;
460 
461  /** This method is called at the end of each "prediction-update-map
462  * insertion" cycle within
463  * "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
464  * This method should normally do nothing, but in some cases can be used
465  * to free auxiliary cached variables.
466  */
467  void auxParticleFilterCleanUp() override;
468 
469  /** Returns a 3D object representing the map.
470  */
471  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
472 
473  /** If the map is a simple point map or it's a multi-metric map that
474  * contains EXACTLY one simple point map, return it.
475  * Otherwise, return NULL
476  */
478  const override;
480 
481  /** An auxiliary variable that can be used freely by the users (this will be
482  * copied to other maps using the copy constructor, copy operator,
483  * streaming,etc) The default value is 0.
484  */
485  unsigned int m_ID;
486 
487 }; // End of class def.
488 
489 } // namespace maps
490 } // namespace mrpt
491 
492 #endif
CGasConcentrationGridMap2D.h
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMap::Ptr, TListMaps >::const_ptr_t
const typename mrpt::maps::CSimplePointsMap::Ptr ::element_type * const_ptr_t
Definition: CMultiMetricMap.h:221
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass< mrpt::maps::CColouredPointsMap::Ptr, TListMaps >::const_ptr_t
const typename mrpt::maps::CColouredPointsMap::Ptr ::element_type * const_ptr_t
Definition: CMultiMetricMap.h:285
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::operator=
ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(const ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &o)
Definition: CMultiMetricMap.h:292
mrpt::maps::CMultiMetricMap::m_ID
unsigned int m_ID
An auxiliary variable that can be used freely by the users (this will be copied to other maps using t...
Definition: CMultiMetricMap.h:485
mrpt::maps::CMultiMetricMap::m_weightedPointsMap
ProxySelectorContainerByClass< mrpt::maps::CWeightedPointsMap::Ptr, TListMaps > m_weightedPointsMap
Proxy that looks like a smart pointer to the first matching object in maps.
Definition: CMultiMetricMap.h:400
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMap::Ptr, TListMaps >::ptr_t
typename mrpt::maps::CSimplePointsMap::Ptr ::element_type * ptr_t
Definition: CMultiMetricMap.h:220
COccupancyGridMap2D.h
const_iterator
const Scalar * const_iterator
Definition: eigen_plugins.h:27
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::get
ptr_t get()
Definition: CMultiMetricMap.h:319
mrpt::rtti::TRuntimeClassId
A structure that holds runtime class type information.
Definition: CObject.h:30
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::operator->
ptr_t operator->() const
Definition: CMultiMetricMap.h:324
mrpt::maps::CMultiMetricMap::m_heightMRFMaps
ProxyFilterContainerByClass< mrpt::maps::CHeightGridMap2D_MRF::Ptr, TListMaps > m_heightMRFMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:386
CBeaconMap.h
mrpt::maps::CMultiMetricMap::determineMatching2D
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::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:
Definition: CMultiMetricMap.cpp:343
mrpt::maps::CMultiMetricMap::m_reflectivityMaps
ProxyFilterContainerByClass< mrpt::maps::CReflectivityGridMap2D::Ptr, TListMaps > m_reflectivityMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:390
mrpt::maps::CMultiMetricMap::isEmpty
bool isEmpty() const override
Returns true if all maps returns true to their isEmpty() method, which is map-dependent.
Definition: CMultiMetricMap.cpp:360
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass< mrpt::maps::CColouredPointsMap::Ptr, TListMaps >::ptr_t
typename mrpt::maps::CColouredPointsMap::Ptr ::element_type * ptr_t
Definition: CMultiMetricMap.h:284
mrpt::maps::CMultiMetricMap::getAsSimplePointsMap
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple point map or it's a multi-metric map that contains EXACTLY one simple point ma...
Definition: CMultiMetricMap.cpp:440
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass< mrpt::maps::CColouredPointsMap::Ptr, TListMaps >::pointee_t
typename mrpt::maps::CColouredPointsMap::Ptr ::element_type pointee_t
Definition: CMultiMetricMap.h:283
mrpt::maps::CMultiMetricMap::auxParticleFilterCleanUp
void auxParticleFilterCleanUp() override
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
Definition: CMultiMetricMap.cpp:428
CWirelessPowerGridMap2D.h
mrpt::maps::CWirelessPowerGridMap2D::Ptr
std::shared_ptr< CWirelessPowerGridMap2D > Ptr
Definition: CWirelessPowerGridMap2D.h:37
mrpt::maps::CMultiMetricMap::m_beaconMap
ProxySelectorContainerByClass< mrpt::maps::CBeaconMap::Ptr, TListMaps > m_beaconMap
Proxy that looks like a smart pointer to the first matching object in maps.
Definition: CMultiMetricMap.h:408
mrpt::maps::CMultiMetricMap::internal_insertObservation
bool internal_insertObservation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
Definition: CMultiMetricMap.cpp:331
COctoMap.h
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::size
size_t size() const
Definition: CMultiMetricMap.h:245
mrpt::maps::CMultiMetricMap::getMapByClass
T::Ptr getMapByClass(const size_t &ith=0) const
Returns the i'th observation of a given class (or of a descendant class), or nullptr if there is no s...
Definition: CMultiMetricMap.h:199
mrpt::maps::TMatchingRatioParams
Parameters for CMetricMap::compute3DMatchingRatio()
Definition: metric_map_types.h:75
mrpt::maps::CMultiMetricMap::m_gridMaps
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2D::Ptr, TListMaps > m_gridMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:365
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass
A proxy like ProxyFilterContainerByClass, but it directly appears as if it was a single smart pointer...
Definition: CMultiMetricMap.h:281
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::ProxySelectorContainerByClass
ProxySelectorContainerByClass(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&)
Definition: CMultiMetricMap.h:298
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::maps::CMultiMetricMap::operator=
CMultiMetricMap & operator=(const CMultiMetricMap &o)
Definition: CMultiMetricMap.cpp:197
mrpt::maps::CMultiMetricMap::m_colourOctoMaps
ProxyFilterContainerByClass< mrpt::maps::CColouredOctoMap::Ptr, TListMaps > m_colourOctoMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:371
mrpt::maps::CMultiMetricMap::m_landmarksMap
ProxySelectorContainerByClass< mrpt::maps::CLandmarksMap::Ptr, TListMaps > m_landmarksMap
Proxy that looks like a smart pointer to the first matching object in maps.
Definition: CMultiMetricMap.h:404
mrpt::maps::CMultiMetricMap::CMultiMetricMap
CMultiMetricMap(const mrpt::maps::TSetOfMetricMapInitializers *initializers=nullptr)
Constructor.
Definition: CMultiMetricMap.cpp:183
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::operator[]
SELECTED_CLASS_PTR operator[](size_t index) const
Definition: CMultiMetricMap.h:253
mrpt::maps::CColouredPointsMap::Ptr
std::shared_ptr< CColouredPointsMap > Ptr
Definition: CColouredPointsMap.h:31
mrpt::maps::CMultiMetricMap::m_pointsMaps
ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMap::Ptr, TListMaps > m_pointsMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:362
CMetricMap.h
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::operator=
ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(const ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &o)
Definition: CMultiMetricMap.h:229
source
GLsizei GLsizei GLchar * source
Definition: glext.h:4082
mrpt::maps::TSetOfMetricMapInitializers
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Definition: TMetricMapInitializer.h:91
mrpt::maps::CMultiMetricMap::internal_canComputeObservationLikelihood
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...
Definition: CMultiMetricMap.cpp:316
mrpt::maps::CMultiMetricMap::begin
iterator begin()
Definition: CMultiMetricMap.h:182
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::operator=
ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&o)
Definition: CMultiMetricMap.h:303
mrpt::maps::CMultiMetricMap::getMapByIndex
mrpt::maps::CMetricMap::Ptr getMapByIndex(size_t idx) const
Gets the i-th map.
Definition: CMultiMetricMap.cpp:462
mrpt::maps::CMetricMap
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:56
mrpt::maps::CMultiMetricMap::internal_computeObservationLikelihood
double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
Definition: CMultiMetricMap.cpp:303
CLandmarksMap.h
mrpt::maps::CGasConcentrationGridMap2D::Ptr
std::shared_ptr< CGasConcentrationGridMap2D > Ptr
Definition: CGasConcentrationGridMap2D.h:37
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::m_source
CONTAINER * m_source
Definition: CMultiMetricMap.h:342
mrpt::poses::CPose2D
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle.
Definition: CPose2D.h:40
CColouredOctoMap.h
mrpt::maps::CMultiMetricMap
This class stores any customizable set of metric maps.
Definition: CMultiMetricMap.h:141
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
index
GLuint index
Definition: glext.h:4054
mrpt::maps::CMultiMetricMap::compute3DMatchingRatio
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...
Definition: CMultiMetricMap.cpp:400
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::operator=
ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > & operator=(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&o)
Definition: CMultiMetricMap.h:239
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::m_source
CONTAINER * m_source
Definition: CMultiMetricMap.h:274
TEnumType.h
mrpt::maps::CSimplePointsMap
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.
Definition: CSimplePointsMap.h:31
mrpt::maps::CMetricMap::Ptr
std::shared_ptr< CMetricMap > Ptr
Definition: CMetricMap.h:59
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::m_ret
SELECTED_CLASS_PTR m_ret
Definition: CMultiMetricMap.h:343
obs_frwds.h
mrpt::containers::deepcopy_poly_ptr< mrpt::maps::CMetricMap::Ptr >
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::operator*
pointee_t & operator*() const
Definition: CMultiMetricMap.h:332
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::ProxySelectorContainerByClass
ProxySelectorContainerByClass(CONTAINER &source)
Definition: CMultiMetricMap.h:286
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::empty
bool empty() const
Definition: CMultiMetricMap.h:244
CReflectivityGridMap2D.h
mrpt::opengl::CSetOfObjects::Ptr
std::shared_ptr< CSetOfObjects > Ptr
Definition: CSetOfObjects.h:30
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::push_back
void push_back(const ELEMENT &element)
Definition: CMultiMetricMap.h:268
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::ProxyFilterContainerByClass
ProxyFilterContainerByClass(CONTAINER &source)
Definition: CMultiMetricMap.h:222
mrpt::maps::TMatchingParams
Parameters for the determination of matchings between point clouds, etc.
Definition: metric_map_types.h:22
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::internal_update_ref
void internal_update_ref() const
Definition: CMultiMetricMap.h:344
mrpt::maps::CMultiMetricMap::maps
TListMaps maps
The list of MRPT metric maps in this object.
Definition: CMultiMetricMap.h:178
mrpt::maps::CMultiMetricMap::m_heightMaps
ProxyFilterContainerByClass< mrpt::maps::CHeightGridMap2D::Ptr, TListMaps > m_heightMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:382
mrpt::maps::CMultiMetricMap::internal_clear
void internal_clear() override
Clear all elements of the map.
Definition: CMultiMetricMap.cpp:251
mrpt::maps::CMultiMetricMap::end
const_iterator end() const
Definition: CMultiMetricMap.h:185
mrpt::maps::CMultiMetricMap::TListMaps
std::deque< mrpt::containers::deepcopy_poly_ptr< mrpt::maps::CMetricMap::Ptr > > TListMaps
Definition: CMultiMetricMap.h:171
mrpt::maps::CMultiMetricMap::begin
const_iterator begin() const
Definition: CMultiMetricMap.h:183
mrpt::maps::CMultiMetricMap::saveMetricMapRepresentationToFile
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
The implementation in this class just calls all the corresponding method of the contained metric maps...
Definition: CMultiMetricMap.cpp:368
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::ProxyFilterContainerByClass
ProxyFilterContainerByClass(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &&)
Definition: CMultiMetricMap.h:234
mrpt::maps::CHeightGridMap2D_MRF::Ptr
std::shared_ptr< CHeightGridMap2D_MRF > Ptr
Definition: CHeightGridMap2D_MRF.h:39
CLoadableOptions.h
CHeightGridMap2D.h
mrpt::maps::CMultiMetricMap::iterator
TListMaps::iterator iterator
Definition: CMultiMetricMap.h:180
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:102
CWeightedPointsMap.h
mrpt::maps::CMultiMetricMap::end
iterator end()
Definition: CMultiMetricMap.h:184
mrpt::maps::CMultiMetricMap::setListOfMaps
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &initializers)
This is an overloaded member function, provided for convenience. It differs from the above function o...
Definition: CMultiMetricMap.h:431
CHeightGridMap2D_MRF.h
mrpt::maps::CMultiMetricMap::m_wifiGridMaps
ProxyFilterContainerByClass< mrpt::maps::CWirelessPowerGridMap2D::Ptr, TListMaps > m_wifiGridMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:379
deepcopy_poly_ptr.h
mrpt::obs::CObservation
Declares a class that represents any robot's observation.
Definition: CObservation.h:43
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass
Takes a const ref of a STL non-associative container of smart pointers at construction and exposes an...
Definition: CMultiMetricMap.h:218
mrpt::tfest::TMatchingPairList
A list of TMatchingPair.
Definition: TMatchingPair.h:83
mrpt::maps::CMultiMetricMap::m_octoMaps
ProxyFilterContainerByClass< mrpt::maps::COctoMap::Ptr, TListMaps > m_octoMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:368
CColouredPointsMap.h
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::maps::CMultiMetricMap::setListOfMaps
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers *initializers)
Sets the list of internal map according to the passed list of map initializers (Current maps' content...
Definition: CMultiMetricMap.cpp:219
mrpt::maps::CReflectivityGridMap2D::Ptr
std::shared_ptr< CReflectivityGridMap2D > Ptr
Definition: CReflectivityGridMap2D.h:45
iterator
Scalar * iterator
Definition: eigen_plugins.h:26
mrpt::maps::CMultiMetricMap::getAs3DObject
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Definition: CMultiMetricMap.cpp:390
mrpt::maps::TMatchingExtraResults
Additional results from the determination of matchings between point clouds, etc.,...
Definition: metric_map_types.h:62
mrpt::maps::CMultiMetricMap::const_iterator
TListMaps::const_iterator const_iterator
Definition: CMultiMetricMap.h:181
mrpt::maps::CMultiMetricMap::deleteAllMaps
void deleteAllMaps()
Deletes all maps and clears the internal lists of maps (with clear_unique(), so user copies remain al...
Definition: CMultiMetricMap.cpp:258
CSerializable.h
CSimplePointsMap.h
mrpt::maps::CMultiMetricMap::ProxyFilterContainerByClass::ProxyFilterContainerByClass
ProxyFilterContainerByClass(ProxyFilterContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &)
Definition: CMultiMetricMap.h:223
mrpt::maps::CMultiMetricMap::m_colourPointsMap
ProxySelectorContainerByClass< mrpt::maps::CColouredPointsMap::Ptr, TListMaps > m_colourPointsMap
Proxy that looks like a smart pointer to the first matching object in maps.
Definition: CMultiMetricMap.h:395
mrpt::maps::CMultiMetricMap::m_gasGridMaps
ProxyFilterContainerByClass< mrpt::maps::CGasConcentrationGridMap2D::Ptr, TListMaps > m_gasGridMaps
STL-like proxy to access this kind of maps in maps.
Definition: CMultiMetricMap.h:375
params
GLenum const GLfloat * params
Definition: glext.h:3534
mrpt::maps::CMultiMetricMap::ProxySelectorContainerByClass::ProxySelectorContainerByClass
ProxySelectorContainerByClass(ProxySelectorContainerByClass< SELECTED_CLASS_PTR, CONTAINER > &)
Definition: CMultiMetricMap.h:287
mrpt::maps::CWeightedPointsMap::Ptr
std::shared_ptr< CWeightedPointsMap > Ptr
Definition: CWeightedPointsMap.h:32



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST