Main MRPT website > C++ reference for MRPT 1.9.9
CMultiMetricMapPDF.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 CMultiMetricMapPDF_H
10 #define CMultiMetricMapPDF_H
11 
13 #include <mrpt/maps/CSimpleMap.h>
16 
18 
21 #include <mrpt/slam/CICP.h>
22 
24 
25 namespace mrpt
26 {
27 namespace slam
28 {
30 }
31 namespace maps
32 {
33 /** Auxiliary class used in mrpt::maps::CMultiMetricMapPDF
34  * \ingroup mrpt_slam_grp
35  */
37 {
39  public:
41  const TSetOfMetricMapInitializers* mapsInitializers = nullptr)
42  : mapTillNow(mapsInitializers), robotPath()
43  {
44  }
45 
47  std::deque<mrpt::math::TPose3D> robotPath;
48 };
49 
50 /** Declares a class that represents a Rao-Blackwellized set of particles for
51  * solving the SLAM problem (This class is the base of RBPF-SLAM applications).
52  * This class is used internally by the map building algorithm in
53  * "mrpt::slam::CMetricMapBuilderRBPF"
54  *
55  * \sa mrpt::slam::CMetricMapBuilderRBPF
56  * \ingroup metric_slam_grp
57  */
60  public mrpt::bayes::CParticleFilterData<CRBPFParticleData>,
62  CMultiMetricMapPDF,
63  mrpt::bayes::CParticleFilterData<CRBPFParticleData>::CParticleList>,
65  CRBPFParticleData, CMultiMetricMapPDF,
66  mrpt::bayes::particle_storage_mode::POINTER>
67 {
69 
71 
72  protected:
73  // PF algorithm implementations:
75  const mrpt::obs::CActionCollection* action,
76  const mrpt::obs::CSensoryFrame* observation,
78  override;
80  const mrpt::obs::CActionCollection* action,
81  const mrpt::obs::CSensoryFrame* observation,
83  override;
85  const mrpt::obs::CActionCollection* action,
86  const mrpt::obs::CSensoryFrame* observation,
88  override;
90  const mrpt::obs::CActionCollection* action,
91  const mrpt::obs::CSensoryFrame* observation,
93  override;
94 
95  private:
96  /** Internal buffer for the averaged map. */
99 
100  /** The SFs and their corresponding pose estimations */
102  /** A mapping between indexes in the SFs to indexes in the robot paths from
103  * particles. */
104  std::vector<uint32_t> SF2robotPath;
105 
106  public:
107  /** The struct for passing extra simulation parameters to the
108  * prediction/update stage
109  * when running a particle filter.
110  * \sa prediction_and_update
111  */
113  {
114  /** Default settings method */
116 
117  void loadFromConfigFile(
119  const std::string& section) override; // See base docs
120  void dumpToTextStream(
121  std::ostream& out) const override; // See base docs
122 
123  /** [pf optimal proposal only] Only for PF algorithm=2 (Exact
124  * "pfOptimalProposal")
125  * Select the map on which to calculate the optimal
126  * proposal distribution. Values:
127  * 0: Gridmap -> Uses Scan matching-based approximation (based on
128  * Stachniss' work)
129  * 1: Landmarks -> Uses matching to approximate optimal
130  * 2: Beacons -> Used for exact optimal proposal in RO-SLAM
131  * 3: Pointsmap -> Uses Scan matching-based approximation with a map
132  * of points (based on Stachniss' work)
133  * Default = 0
134  */
136 
137  /** [prediction stage][pf optimal proposal only] If
138  * useICPGlobalAlign_withGrid=true, this is the minimum quality ratio
139  * [0,1] of the alignment such as it will be accepted. Otherwise, raw
140  * odometry is used for those bad cases (default=0.7).
141  */
143 
144  /** [update stage] If the likelihood is computed through the occupancy
145  * grid map, then this structure is passed to the map when updating the
146  * particles weights in the update stage.
147  */
149 
151 
152  /** ICP parameters, used only when "PF_algorithm=2" in the particle
153  * filter. */
155 
156  } options;
157 
158  /** Constructor
159  */
163  const mrpt::maps::TSetOfMetricMapInitializers* mapsInitializers =
164  nullptr,
165  const TPredictionParams* predictionOptions = nullptr);
166 
167  /** Clear all elements of the maps, and restore all paths to a single
168  * starting pose */
169  void clear(const mrpt::poses::CPose2D& initialPose);
170  /** \overload */
171  void clear(const mrpt::poses::CPose3D& initialPose);
172  /** Resets the map by loading an already-mapped map for past poses.
173  * Current robot pose should be normally set to the last keyframe
174  * in the simplemap. */
175  void clear(
176  const mrpt::maps::CSimpleMap& prevMap,
177  const mrpt::poses::CPose3D& currentPose);
178 
179  /** Returns the estimate of the robot pose as a particles PDF for the
180  * instant of time "timeStep", from 0 to N-1.
181  * \sa getEstimatedPosePDF
182  */
184  size_t timeStep,
185  mrpt::poses::CPose3DPDFParticles& out_estimation) const;
186 
187  /** Returns the current estimate of the robot pose, as a particles PDF.
188  * \sa getEstimatedPosePDFAtTime
189  */
190  void getEstimatedPosePDF(
191  mrpt::poses::CPose3DPDFParticles& out_estimation) const;
192 
193  /** Returns the weighted averaged map based on the current best estimation.
194  * If you need a persistent copy of this object, please use
195  * "CSerializable::duplicate" and use the copy.
196  * \sa Almost 100% sure you would prefer the best current map, given by
197  * getCurrentMostLikelyMetricMap()
198  */
200 
201  /** Returns a pointer to the current most likely map (associated to the most
202  * likely particle) */
204 
205  /** Get the number of CSensoryFrame inserted into the internal member SFs */
206  size_t getNumberOfObservationsInSimplemap() const { return SFs.size(); }
207  /** Insert an observation to the map, at each particle's pose and to each
208  * particle's metric map.
209  * \param sf The SF to be inserted
210  * \return true if any may was updated, false otherwise
211  */
213 
214  /** Return the path (in absolute coordinate poses) for the i'th particle.
215  * \exception On index out of bounds
216  */
217  void getPath(size_t i, std::deque<math::TPose3D>& out_path) const;
218 
219  /** Returns the current entropy of paths, computed as the average entropy of
220  * poses along the path, where entropy of each pose estimation is computed
221  * as the entropy of the gaussian approximation covariance.
222  */
223  double getCurrentEntropyOfPaths();
224 
225  /** Returns the joint entropy estimation over paths and maps, acording to
226  * "Information Gain-based Exploration Using" by C. Stachniss, G. Grissetti
227  * and W.Burgard.
228  */
229  double getCurrentJointEntropy();
230 
231  /** Update the poses estimation of the member "SFs" according to the current
232  * path belief.
233  */
235 
236  /** A logging utility: saves the current path estimation for each particle
237  * in a text file (a row per particle, each 3-column-entry is a set
238  * [x,y,phi], respectively).
239  */
241 
242  private:
243  /** Rebuild the "expected" grid map. Used internally, do not call */
244  void rebuildAverageMap();
245 
246  /** An index [0,1] measuring how much information an observation aports to
247  * the map (Typ. threshold=0.07) */
249 
250  public:
251  /** \name Virtual methods that the PF_implementations assume exist.
252  @{ */
253 
254  // see docs in base
256  const size_t i, bool& pose_is_valid) const override;
257 
259  CParticleDataContent* particleData,
260  const mrpt::math::TPose3D& newPose) const override;
261 
262  // The base implementation is fine for this class.
263  // void PF_SLAM_implementation_replaceByNewParticleSet( ...
264 
266  const CParticleList& particles,
267  const mrpt::obs::CSensoryFrame* sf) const override;
268 
269  bool PF_SLAM_implementation_skipRobotMovement() const override;
270 
271  /** Evaluate the observation likelihood for one particle at a given location
272  */
275  const size_t particleIndexForMap,
276  const mrpt::obs::CSensoryFrame& observation,
277  const mrpt::poses::CPose3D& x) const override;
278  /** @} */
279 
280 }; // End of class def.
281 
282 } // End of namespace
283 } // End of namespace
284 
285 #endif
mrpt::maps::CMultiMetricMapPDF::insertObservation
bool insertObservation(mrpt::obs::CSensoryFrame &sf)
Insert an observation to the map, at each particle's pose and to each particle's metric map.
Definition: CMultiMetricMapPDF.cpp:408
mrpt::bayes::CParticleFilterData< CRBPFParticleData >::CParticleList
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
Definition: CParticleFilterData.h:214
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::loadFromConfigFile
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
Definition: CMultiMetricMapPDF.cpp:639
mrpt::maps::CMultiMetricMapPDF::saveCurrentPathEstimationToTextFile
void saveCurrentPathEstimationToTextFile(const std::string &fil)
A logging utility: saves the current path estimation for each particle in a text file (a row per part...
Definition: CMultiMetricMapPDF.cpp:579
CPoseRandomSampler.h
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::pfOptimalProposal_mapSelection
int pfOptimalProposal_mapSelection
[pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on whic...
Definition: CMultiMetricMapPDF.h:135
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::KLD_params
mrpt::slam::TKLDParams KLD_params
Definition: CMultiMetricMapPDF.h:150
mrpt::maps::CMultiMetricMapPDF::PF_SLAM_implementation_custom_update_particle_with_new_pose
void PF_SLAM_implementation_custom_update_particle_with_new_pose(CParticleDataContent *particleData, const mrpt::math::TPose3D &newPose) const override
Definition: CMultiMetricMapPDF_RBPF.cpp:993
mrpt::maps::CRBPFParticleData
Auxiliary class used in mrpt::maps::CMultiMetricMapPDF.
Definition: CMultiMetricMapPDF.h:36
CMultiMetricMap.h
mrpt::slam::CICP::TConfigParams
The ICP algorithm configuration data.
Definition: CICP.h:72
mrpt::maps::CMultiMetricMapPDF::PF_SLAM_computeObservationLikelihoodForParticle
double PF_SLAM_computeObservationLikelihoodForParticle(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const size_t particleIndexForMap, const mrpt::obs::CSensoryFrame &observation, const mrpt::poses::CPose3D &x) const override
Evaluate the observation likelihood for one particle at a given location.
Definition: CMultiMetricMapPDF_RBPF.cpp:1021
mrpt::maps::CMultiMetricMapPDF::clear
void clear(const mrpt::poses::CPose2D &initialPose)
Clear all elements of the maps, and restore all paths to a single starting pose.
Definition: CMultiMetricMapPDF.cpp:75
mrpt::slam::TKLDParams
Option set for KLD algorithm.
Definition: TKLDParams.h:20
mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfAuxiliaryPFOptimal
void prediction_and_update_pfAuxiliaryPFOptimal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Performs the particle filter prediction/update stages for the algorithm "pfAuxiliaryPFOptimal" (if no...
Definition: CMultiMetricMapPDF_RBPF.cpp:145
mrpt::maps::CMultiMetricMapPDF::getPath
void getPath(size_t i, std::deque< math::TPose3D > &out_path) const
Return the path (in absolute coordinate poses) for the i'th particle.
Definition: CMultiMetricMapPDF.cpp:441
mrpt::maps::CMultiMetricMapPDF::getCurrentMostLikelyMetricMap
const CMultiMetricMap * getCurrentMostLikelyMetricMap() const
Returns a pointer to the current most likely map (associated to the most likely particle)
Definition: CMultiMetricMapPDF.cpp:533
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::ICPGlobalAlign_MinQuality
float ICPGlobalAlign_MinQuality
[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum ...
Definition: CMultiMetricMapPDF.h:142
mrpt::slam::CMetricMapBuilderRBPF
This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM).
Definition: CMetricMapBuilderRBPF.h:58
CICP.h
PF_implementations_data.h
mrpt::maps::CMultiMetricMapPDF::averageMap
mrpt::maps::CMultiMetricMap averageMap
Internal buffer for the averaged map.
Definition: CMultiMetricMapPDF.h:97
mrpt::obs::CActionCollection
Declares a class for storing a collection of robot actions.
Definition: CActionCollection.h:28
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::maps::CMultiMetricMapPDF::averageMapIsUpdated
bool averageMapIsUpdated
Definition: CMultiMetricMapPDF.h:98
mrpt::maps::CMultiMetricMapPDF::getEstimatedPosePDFAtTime
void getEstimatedPosePDFAtTime(size_t timeStep, mrpt::poses::CPose3DPDFParticles &out_estimation) const
Returns the estimate of the robot pose as a particles PDF for the instant of time "timeStep",...
Definition: CMultiMetricMapPDF.cpp:182
mrpt::maps::CRBPFParticleData::robotPath
std::deque< mrpt::math::TPose3D > robotPath
Definition: CMultiMetricMapPDF.h:47
mrpt::maps::CMultiMetricMapPDF::SFs
mrpt::maps::CSimpleMap SFs
The SFs and their corresponding pose estimations.
Definition: CMultiMetricMapPDF.h:101
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::CMultiMetricMapPDF::PF_SLAM_implementation_skipRobotMovement
bool PF_SLAM_implementation_skipRobotMovement() const override
Do not move the particles until the map is populated.
Definition: CMultiMetricMapPDF_RBPF.cpp:1012
mrpt::obs::CSensoryFrame
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:54
mrpt::bayes::CParticleFilterData< CRBPFParticleData >::CParticleDataContent
CRBPFParticleData CParticleDataContent
This is the type inside the corresponding CParticleData class.
Definition: CParticleFilterData.h:210
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::icp_params
mrpt::slam::CICP::TConfigParams icp_params
ICP parameters, used only when "PF_algorithm=2" in the particle filter.
Definition: CMultiMetricMapPDF.h:154
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
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
mrpt::maps::CMultiMetricMap
This class stores any customizable set of metric maps.
Definition: CMultiMetricMap.h:141
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::update_gridMapLikelihoodOptions
COccupancyGridMap2D::TLikelihoodOptions update_gridMapLikelihoodOptions
[update stage] If the likelihood is computed through the occupancy grid map, then this structure is p...
Definition: CMultiMetricMapPDF.h:148
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
mrpt::maps::CMultiMetricMapPDF
Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...
Definition: CMultiMetricMapPDF.h:58
mrpt::maps::CMultiMetricMapPDF::getCurrentJointEntropy
double getCurrentJointEntropy()
Returns the joint entropy estimation over paths and maps, acording to "Information Gain-based Explora...
Definition: CMultiMetricMapPDF.cpp:481
mrpt::maps::CSimpleMap::size
size_t size() const
Returns the count of pairs (pose,sensory data)
Definition: CSimpleMap.cpp:53
mrpt::config::CLoadableOptions
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
Definition: config/CLoadableOptions.h:28
mrpt::maps::CMultiMetricMapPDF::getEstimatedPosePDF
void getEstimatedPosePDF(mrpt::poses::CPose3DPDFParticles &out_estimation) const
Returns the current estimate of the robot pose, as a particles PDF.
Definition: CMultiMetricMapPDF.cpp:171
mrpt::serialization::CSerializable
The virtual base class which provides a unified interface for all persistent objects in MRPT.
Definition: CSerializable.h:32
mrpt::slam::PF_implementation
A set of common data shared by PF implementations for both SLAM and localization.
Definition: PF_implementations_data.h:40
mrpt::bayes::CParticleFilterData
This template class declares the array of particles and its internal data, managing some memory-relat...
Definition: CParticleFilterData.h:206
mrpt::maps::CMultiMetricMapPDF::getAveragedMetricMapEstimation
const CMultiMetricMap * getAveragedMetricMapEstimation()
Returns the weighted averaged map based on the current best estimation.
Definition: CMultiMetricMapPDF.cpp:282
mrpt::math::TPose3D
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Definition: lightweight_geom_data.h:603
mrpt::poses::CPose3DPDFParticles
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
Definition: CPose3DPDFParticles.h:31
CParticleFilterCapable.h
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
Definition: CMultiMetricMapPDF.cpp:617
mrpt::maps::CRBPFParticleData::mapTillNow
CMultiMetricMap mapTillNow
Definition: CMultiMetricMapPDF.h:46
mrpt::maps::CMultiMetricMapPDF::getLastPose
mrpt::math::TPose3D getLastPose(const size_t i, bool &pose_is_valid) const override
Return the last robot pose in the i'th particle; is_valid_pose will be false if there is no such last...
Definition: CMultiMetricMapPDF.cpp:265
CLoadableOptions.h
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
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::TPredictionParams
TPredictionParams()
Default settings method.
Definition: CMultiMetricMapPDF.cpp:605
mrpt::maps::CSimpleMap
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:35
mrpt::maps::CMultiMetricMapPDF::getCurrentEntropyOfPaths
double getCurrentEntropyOfPaths()
Returns the current entropy of paths, computed as the average entropy of poses along the path,...
Definition: CMultiMetricMapPDF.cpp:451
mrpt::maps::CMultiMetricMapPDF::TPredictionParams
The struct for passing extra simulation parameters to the prediction/update stage when running a part...
Definition: CMultiMetricMapPDF.h:112
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions
With this struct options are provided to the observation likelihood computation process.
Definition: COccupancyGridMap2D.h:571
mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfStandardProposal
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Performs the particle filter prediction/update stages for the algorithm "pfStandardProposal" (if not ...
Definition: CMultiMetricMapPDF_RBPF.cpp:975
mrpt::maps::CMultiMetricMapPDF::options
mrpt::maps::CMultiMetricMapPDF::TPredictionParams options
mrpt::bayes::CParticleFilterDataImpl
A curiously recurring template pattern (CRTP) approach to providing the basic functionality of any CP...
Definition: CParticleFilterData.h:33
mrpt::maps::CMultiMetricMapPDF::rebuildAverageMap
void rebuildAverageMap()
Rebuild the "expected" grid map.
Definition: CMultiMetricMapPDF.cpp:291
mrpt::maps::CMultiMetricMapPDF::PF_SLAM_implementation_doWeHaveValidObservations
bool PF_SLAM_implementation_doWeHaveValidObservations(const CParticleList &particles, const mrpt::obs::CSensoryFrame *sf) const override
Definition: CMultiMetricMapPDF_RBPF.cpp:1000
CSimpleMap.h
mrpt::maps::CMultiMetricMapPDF::updateSensoryFrameSequence
void updateSensoryFrameSequence()
Update the poses estimation of the member "SFs" according to the current path belief.
Definition: CMultiMetricMapPDF.cpp:554
mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfAuxiliaryPFStandard
void prediction_and_update_pfAuxiliaryPFStandard(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Performs the particle filter prediction/update stages for the algorithm "pfAuxiliaryPFStandard" (if n...
Definition: CMultiMetricMapPDF_RBPF.cpp:161
mrpt::maps::CRBPFParticleData::CRBPFParticleData
CRBPFParticleData(const TSetOfMetricMapInitializers *mapsInitializers=nullptr)
Definition: CMultiMetricMapPDF.h:40
mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal
void prediction_and_update_pfOptimalProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Performs the particle filter prediction/update stages for the algorithm "pfOptimalProposal" (if not i...
Definition: CMultiMetricMapPDF_RBPF.cpp:190
CPosePDFParticles.h
mrpt::bayes::CParticleFilter::TParticleFilterOptions
The configuration of a particle filter.
Definition: CParticleFilter.h:102
mrpt::maps::CMultiMetricMapPDF::getNumberOfObservationsInSimplemap
size_t getNumberOfObservationsInSimplemap() const
Get the number of CSensoryFrame inserted into the internal member SFs.
Definition: CMultiMetricMapPDF.h:206
x
GLenum GLint x
Definition: glext.h:3538
mrpt::maps::CMultiMetricMapPDF::newInfoIndex
float newInfoIndex
An index [0,1] measuring how much information an observation aports to the map (Typ.
Definition: CMultiMetricMapPDF.h:248
CPose3DPDFParticles.h
mrpt::maps::CMultiMetricMapPDF::CMultiMetricMapPDF
CMultiMetricMapPDF(const bayes::CParticleFilter::TParticleFilterOptions &opts=bayes::CParticleFilter::TParticleFilterOptions(), const mrpt::maps::TSetOfMetricMapInitializers *mapsInitializers=nullptr, const TPredictionParams *predictionOptions=nullptr)
Constructor.
Definition: CMultiMetricMapPDF.cpp:45
mrpt::maps::CMultiMetricMapPDF::SF2robotPath
std::vector< uint32_t > SF2robotPath
A mapping between indexes in the SFs to indexes in the robot paths from particles.
Definition: CMultiMetricMapPDF.h:104



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