MRPT  2.0.4
CMultiMetricMap.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
13 #include <mrpt/maps/CMetricMap.h>
14 #include <mrpt/obs/obs_frwds.h>
17 
18 namespace mrpt::maps
19 {
20 class TSetOfMetricMapInitializers;
21 
22 /** This class stores any customizable set of metric maps.
23  * The internal metric maps can be accessed directly by the user as smart
24  *pointers with CMultiMetricMap::mapByIndex() or via `iterator`s.
25  * The utility of this container is to operate on several maps simultaneously:
26  *update them by inserting observations,
27  * evaluate the likelihood of one observation by fusing (multiplying) the
28  *likelihoods over the different maps, etc.
29  *
30  * <b>These kinds of metric maps can be kept inside</b> (list may be
31  *incomplete, refer to classes derived from mrpt::maps::CMetricMap):
32  * - mrpt::maps::CSimplePointsMap: For 2D or 3D range scans, ...
33  * - mrpt::maps::COccupancyGridMap2D: 2D, <b>horizontal</b> laser range
34  *scans, at different altitudes.
35  * - mrpt::maps::COctoMap: For 3D occupancy grids of variable resolution,
36  *with octrees (based on the library `octomap`).
37  * - mrpt::maps::CColouredOctoMap: The same than above, but nodes can store
38  *RGB data appart from occupancy.
39  * - mrpt::maps::CLandmarksMap: For visual landmarks,etc...
40  * - mrpt::maps::CGasConcentrationGridMap2D: For gas concentration maps.
41  * - mrpt::maps::CWirelessPowerGridMap2D: For wifi power maps.
42  * - mrpt::maps::CBeaconMap: For range-only SLAM.
43  * - mrpt::maps::CHeightGridMap2D: For elevation maps of height for each
44  *(x,y) location (Digital elevation model, DEM)
45  * - mrpt::maps::CHeightGridMap2D_MRF: DEMs as Markov Random Field (MRF)
46  * - mrpt::maps::CReflectivityGridMap2D: For maps of "reflectivity" for
47  *each
48  *(x,y) location.
49  * - mrpt::maps::CColouredPointsMap: For point map with color.
50  * - mrpt::maps::CWeightedPointsMap: For point map with weights (capable of
51  *"fusing").
52  *
53  * See CMultiMetricMap::setListOfMaps() for the method for initializing this
54  *class programmatically.
55  * See also TSetOfMetricMapInitializers::loadFromConfigFile for a template of
56  *".ini"-like configuration
57  * file that can be used to define which maps to create and all their
58  *parameters.
59  * Alternatively, the list of maps is public so it can be directly
60  *manipulated/accessed in CMultiMetricMap::maps
61  *
62  * Configuring the list of maps: Alternatives
63  * --------------------------------------------
64  *
65  * **Method #1: Using map definition structures**
66  * \code
67  * mrpt::maps::TSetOfMetricMapInitializers map_inits;
68  * {
69  * mrpt::maps::COccupancyGridMap2D::TMapDefinition def;
70  * def.resolution = 0.05;
71  * def.insertionOpts.maxOccupancyUpdateCertainty = 0.8;
72  * def.insertionOpts.maxDistanceInsertion = 30;
73  * map_inits.push_back(def);
74  * }
75  * {
76  * mrpt::maps::CSimplePointsMap::TMapDefinition def;
77  * map_inits.push_back(def);
78  * }
79  * mrpt::maps::CMultiMetricMap theMap;
80  * theMap.setListOfMaps(map_inits);
81  * \endcode
82  *
83  * **Method #2: Using a configuration file**
84  * See TSetOfMetricMapInitializers::loadFromConfigFile() for details on expected
85  *file format.
86  *
87  * \code
88  * mrpt::config::CConfigFile cfgFile("file.cfg");
89  * mrpt::maps::TSetOfMetricMapInitializers map_inits;
90  * map_inits.loadFromConfigFile(cfgFile, "MapDefinition");
91  *
92  * mrpt::maps::CMultiMetricMap theMap;
93  * theMap.setListOfMaps(map_inits);
94  * \endcode
95  *
96  * **Method #3: Manual manipulation**
97  *
98  * \code
99  * mrpt::maps::CMultiMetricMap theMap;
100  * {
101  * auto ptMap = mrpt::maps::CSimplePointsMap::Create();
102  * theMap.maps.push_back(ptMap);
103  * }
104  * \endcode
105  *
106  * \note [New in MRPT 1.3.0]: `likelihoodMapSelection`, which selected the map
107  *to be used when
108  * computing the likelihood of an observation, has been removed. Use the
109  *`enableObservationLikelihood`
110  * property of each individual map declaration.
111  *
112  * \note [New in MRPT 1.3.0]: `enableInsertion_{pointsMap,...}` have been also
113  *removed.
114  * Use the `enableObservationInsertion` property of each map declaration.
115  *
116  * \note This class belongs to [mrpt-slam] instead of [mrpt-maps] due to the
117  *dependency on map classes in mrpt-vision.
118  * \sa CMetricMap \ingroup mrpt_maps_grp
119  */
121 {
123  public:
124  /** @name Access to list of maps
125  @{ */
126  using TListMaps = std::deque<
128 
129  /** The list of metric maps in this object. Use dynamic_cast or smart
130  * pointer-based downcast to access maps by their actual type.
131  * You can directly manipulate this list. Helper methods to initialize it
132  * are described in the docs of CMultiMetricMap
133  */
135 
136  using iterator = TListMaps::iterator;
137  using const_iterator = TListMaps::const_iterator;
138  iterator begin() { return maps.begin(); }
139  const_iterator begin() const { return maps.begin(); }
140  iterator end() { return maps.end(); }
141  const_iterator end() const { return maps.end(); }
142 
143  /** Gets the i-th map \excepmapByIndextime_error On out-of-bounds */
144  mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const;
145 
146  /** Returns the i'th map of a given class (or of a derived
147  * class), or empty smart pointer if there is no such map.
148  * Example:
149  * \code
150  * COccupancyGridMap2D::Ptr obs =
151  * multimap.mapByClass<COccupancyGridMap2D>();
152  * \endcode
153  * By default (ith=0), the first match is returned.
154  */
155  template <typename T>
156  typename T::Ptr mapByClass(size_t ith = 0) const
157  {
158  size_t foundCount = 0;
159  const auto* class_ID = &T::GetRuntimeClassIdStatic();
160  for (const auto& it : *this)
161  if (it->GetRuntimeClass()->derivedFrom(class_ID))
162  if (foundCount++ == ith)
163  return std::dynamic_pointer_cast<T>(it.get_ptr());
164  return typename T::Ptr(); // Not found: return empty smart pointer
165  }
166 
167  /** Count how many maps exist of the given class (or derived class) */
168  template <typename T>
169  typename std::size_t countMapsByClass() const
170  {
171  size_t foundCount = 0;
172  const auto* class_ID = &T::GetRuntimeClassIdStatic();
173  for (const auto& it : *this)
174  if (it->GetRuntimeClass()->derivedFrom(class_ID)) foundCount++;
175  return foundCount;
176  }
177  /** @} */
178 
179  /** Default ctor: empty list of maps */
180  CMultiMetricMap() = default;
181 
182  /** Constructor with a list of map initializers.
183  * \param initializers One internal map will be created for each entry in
184  * this "TSetOfMetricMapInitializers" struct.
185  */
186  CMultiMetricMap(const TSetOfMetricMapInitializers& initializers);
187 
188  /** Sets the list of internal map according to the passed list of map
189  * initializers (current maps will be deleted) */
191 
192  // Implementation of virtual CMetricMap methods.
193  // See docs in base class:
194 
195  /** Returns true if **all** maps returns true in their isEmpty() method */
196  bool isEmpty() const override;
197  void determineMatching2D(
198  const mrpt::maps::CMetricMap* otherMap,
199  const mrpt::poses::CPose2D& otherMapPose,
200  mrpt::tfest::TMatchingPairList& correspondences,
202  mrpt::maps::TMatchingExtraResults& extraResults) const override;
204  const mrpt::maps::CMetricMap* otherMap,
205  const mrpt::poses::CPose3D& otherMapPose,
206  const TMatchingRatioParams& params) const override;
208  const std::string& filNamePrefix) const override;
209  void auxParticleFilterCleanUp() override;
210  void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const override;
211  const mrpt::maps::CSimplePointsMap* getAsSimplePointsMap() const override;
212 
213  protected:
214  // See base class docs:
215  void internal_clear() override;
217  const mrpt::obs::CObservation& obs,
218  const mrpt::poses::CPose3D* robotPose = nullptr) override;
220  const mrpt::obs::CObservation& obs) const override;
222  const mrpt::obs::CObservation& obs,
223  const mrpt::poses::CPose3D& takenFrom) override;
224 
225 }; // End of class def.
226 
227 } // namespace mrpt::maps
void auxParticleFilterCleanUp() override
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
std::size_t countMapsByClass() const
Count how many maps exist of the given class (or derived class)
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Parameters for CMetricMap::compute3DMatchingRatio()
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
mrpt::vision::TStereoCalibParams params
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
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: ...
T::Ptr mapByClass(size_t ith=0) const
Returns the i&#39;th map of a given class (or of a derived class), or empty smart pointer if there is no ...
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
bool isEmpty() const override
Returns true if all maps returns true in their isEmpty() method.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams &params) const override
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.
Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves.
void internal_clear() override
Internal method called by clear()
A list of TMatchingPair.
Definition: TMatchingPair.h:70
CMultiMetricMap()=default
Default ctor: empty list of maps.
bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation &obs) const override
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
Declares a virtual base class for all metric maps storage classes.
Definition: CMetricMap.h:52
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple points map or it&#39;s a multi-metric map that contains EXACTLY one simple points ...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
TListMaps::const_iterator const_iterator
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
TListMaps maps
The list of metric maps in this object.
const_iterator end() const
std::deque< mrpt::containers::deepcopy_poly_ptr< mrpt::maps::CMetricMap::Ptr > > TListMaps
mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const
Gets the i-th map On out-of-bounds.
This class stores any customizable set of metric maps.
Parameters for the determination of matchings between point clouds, etc.
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &init)
Sets the list of internal map according to the passed list of map initializers (current maps will be ...
const_iterator begin() const
TListMaps::iterator iterator



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020