Main MRPT website > C++ reference
MRPT logo
maps/CRandomFieldGridMap2D.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-2015, 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 
10 #ifndef CRandomFieldGridMap2D_H
11 #define CRandomFieldGridMap2D_H
12 
14 #include <mrpt/utils/CImage.h>
16 #include <mrpt/math/CMatrixD.h>
18 #include <mrpt/utils/TEnumType.h>
19 #include <mrpt/maps/CMetricMap.h>
21 
22 #include <mrpt/maps/link_pragmas.h>
23 
24 #if EIGEN_VERSION_AT_LEAST(3,1,0)
25 // #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET // No need to for this macro in Eigen 3.1+
26 # include <Eigen/Sparse>
27 #endif
28 
29 namespace mrpt
30 {
31 namespace maps
32 {
33  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CRandomFieldGridMap2D , CMetricMap, MAPS_IMPEXP )
34 
35  // Pragma defined to ensure no structure packing: since we'll serialize TRandomFieldCell to streams, we want it not to depend on compiler options, etc.
36 #if defined(MRPT_IS_X86_AMD64)
37 #pragma pack(push,1)
38 #endif
39 
40  /** The contents of each cell in a CRandomFieldGridMap2D map.
41  * \ingroup mrpt_maps_grp
42  **/
44  {
45  /** Constructor */
46  TRandomFieldCell(double kfmean_dm_mean = 1e-20, double kfstd_dmmeanw = 0) :
47  kf_mean (kfmean_dm_mean),
48  kf_std (kfstd_dmmeanw),
49  dmv_var_mean (0),
50  last_updated(mrpt::system::now()),
51  updated_std (kfstd_dmmeanw)
52  { }
53 
54  // *Note*: Use unions to share memory between data fields, since only a set
55  // of the variables will be used for each mapping strategy.
56  // You can access to a "TRandomFieldCell *cell" like: cell->kf_mean, cell->kf_std, etc..
57  // but accessing cell->kf_mean would also modify (i.e. ARE the same memory slot) cell->dm_mean, for example.
58 
59  // Note 2: If the number of type of fields are changed in the future,
60  // *PLEASE* also update the writeToStream() and readFromStream() methods!!
61 
62  union
63  {
64  double kf_mean; //!< [KF-methods only] The mean value of this cell
65  double dm_mean; //!< [Kernel-methods only] The cumulative weighted readings of this cell
66  double gmrf_mean; //!< [GMRF only] The mean value of this cell
67  };
68 
69  union
70  {
71  double kf_std; //!< [KF-methods only] The standard deviation value of this cell
72  double dm_mean_w; //!< [Kernel-methods only] The cumulative weights (concentration = alpha * dm_mean / dm_mean_w + (1-alpha)*r0 )
73  double gmrf_std;
74  };
75 
76  double dmv_var_mean; //!< [Kernel DM-V only] The cumulative weighted variance of this cell
77 
78  mrpt::system::TTimeStamp last_updated; //!< [Dynamic maps only] The timestamp of the last time the cell was updated
79  double updated_std; //!< [Dynamic maps only] The std cell value that was updated (to be used in the Forgetting_curve
80  };
81 
82 #if defined(MRPT_IS_X86_AMD64)
83 #pragma pack(pop)
84 #endif
85 
86  /** CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property which is estimated by this map, either
87  * as a simple value or as a probility distribution (for each cell).
88  *
89  * There are a number of methods available to build the gas grid-map, depending on the value of
90  * "TMapRepresentation maptype" passed in the constructor.
91  *
92  * The following papers describe the mapping alternatives implemented here:
93  * - mrKernelDM: A kernel-based method. See:
94  * - "Building gas concentration gridmaps with a mobile robot", Lilienthal, A. and Duckett, T., Robotics and Autonomous Systems, v.48, 2004.
95  * - mrKernelDMV: A kernel-based method. See:
96  * - "A Statistical Approach to Gas Distribution Modelling with Mobile Robots--The Kernel DM+ V Algorithm", Lilienthal, A.J. and Reggente, M. and Trincavelli, M. and Blanco, J.L. and Gonzalez, J., IROS 2009.
97  * - mrKalmanFilter: A "brute-force" approach to estimate the entire map with a dense (linear) Kalman filter. Will be very slow for mid or large maps. It's provided just for comparison purposes, not useful in practice.
98  * - mrKalmanApproximate: A compressed/sparse Kalman filter approach. See:
99  * - "A Kalman Filter Based Approach to Probabilistic Gas Distribution Mapping", JL Blanco, JG Monroy, J Gonzalez-Jimenez, A Lilienthal, 28th Symposium On Applied Computing (SAC), 2013.
100  * - mrGMRF: Time-Varying Gas Distribution Mapping with a Sparse MArkov Random Field estimator. See:
101  * - (under review)
102  *
103  * Note that this class is virtual, since derived classes still have to implement:
104  * - mrpt::maps::CMetricMap::internal_computeObservationLikelihood()
105  * - mrpt::maps::CMetricMap::internal_insertObservation()
106  * - Serialization methods: writeToStream() and readFromStream()
107  *
108  * \sa mrpt::maps::CGasConcentrationGridMap2D, mrpt::maps::CWirelessPowerGridMap2D, mrpt::maps::CMetricMap, mrpt::utils::CDynamicGrid, The application icp-slam, mrpt::maps::CMultiMetricMap
109  * \ingroup mrpt_maps_grp
110  */
111  class CRandomFieldGridMap2D : public mrpt::maps::CMetricMap, public utils::CDynamicGrid<TRandomFieldCell>
112  {
114 
115  // This must be added to any CSerializable derived class:
117  public:
118 
119  /** Calls the base CMetricMap::clear
120  * Declared here to avoid ambiguity between the two clear() in both base classes.
121  */
122  inline void clear() { CMetricMap::clear(); }
123 
124  // This method is just used for the ::saveToTextFile() method in base class.
125  float cell2float(const TRandomFieldCell& c) const
126  {
127  return c.kf_mean;
128  }
129 
130  /** The type of map representation to be used, see CRandomFieldGridMap2D for a discussion.
131  */
133  {
135  mrAchim = 0, //!< Another alias for "mrKernelDM", for backwards compatibility
142  };
143 
144  /** Constructor
145  */
147  TMapRepresentation mapType = mrAchim,
148  float x_min = -2,
149  float x_max = 2,
150  float y_min = -2,
151  float y_max = 2,
152  float resolution = 0.1
153  );
154 
155  /** Destructor */
156  virtual ~CRandomFieldGridMap2D();
157 
158  /** Returns true if the map is empty/no observation has been inserted (in this class it always return false,
159  * unless redefined otherwise in base classes)
160  */
161  virtual bool isEmpty() const;
162 
163 
164  /** Save the current map as a graphical file (BMP,PNG,...).
165  * The file format will be derived from the file extension (see CImage::saveToFile )
166  * It depends on the map representation model:
167  * mrAchim: Each pixel is the ratio \f$ \sum{\frac{wR}{w}} \f$
168  * mrKalmanFilter: Each pixel is the mean value of the Gaussian that represents each cell.
169  *
170  * \sa \a getAsBitmapFile()
171  */
172  virtual void saveAsBitmapFile(const std::string &filName) const;
173 
174  /** Returns an image just as described in \a saveAsBitmapFile */
175  virtual void getAsBitmapFile(mrpt::utils::CImage &out_img) const;
176 
177  /** Parameters common to any derived class.
178  * Derived classes should derive a new struct from this one, plus "public utils::CLoadableOptions",
179  * and call the internal_* methods where appropiate to deal with the variables declared here.
180  * Derived classes instantions of their "TInsertionOptions" MUST set the pointer "m_insertOptions_common" upon construction.
181  */
183  {
184  TInsertionOptionsCommon(); //!< Default values loader
185 
186  /** See utils::CLoadableOptions */
187  void internal_loadFromConfigFile_common(
188  const mrpt::utils::CConfigFileBase &source,
189  const std::string &section);
190 
191  void internal_dumpToTextStream_common(mrpt::utils::CStream &out) const; //!< See utils::CLoadableOptions
192 
193  /** @name Kernel methods (mrKernelDM, mrKernelDMV)
194  @{ */
195  float sigma; //!< The sigma of the "Parzen"-kernel Gaussian
196  float cutoffRadius; //!< The cutoff radius for updating cells.
197  float R_min,R_max; //!< Limits for normalization of sensor readings.
198  double dm_sigma_omega; //!< [DM/DM+V methods] The scaling parameter for the confidence "alpha" values (see the IROS 2009 paper; see CRandomFieldGridMap2D) */
199  /** @} */
200 
201  /** @name Kalman-filter methods (mrKalmanFilter, mrKalmanApproximate)
202  @{ */
203  float KF_covSigma; //!< The "sigma" for the initial covariance value between cells (in meters).
204  float KF_initialCellStd; //!< The initial standard deviation of each cell's concentration (will be stored both at each cell's structure and in the covariance matrix as variances in the diagonal) (in normalized concentration units).
205  float KF_observationModelNoise; //!< The sensor model noise (in normalized concentration units).
206  float KF_defaultCellMeanValue; //!< The default value for the mean of cells' concentration.
207  uint16_t KF_W_size; //!< [mrKalmanApproximate] The size of the window of neighbor cells.
208  /** @} */
209 
210  /** @name Gaussian Markov Random Fields methods (mrGMRF_)
211  @{ */
212  float GMRF_lambdaPrior; //!< The information (Lambda) of fixed map constraints
213  float GMRF_lambdaObs; //!< The initial information (Lambda) of each observation (this information will decrease with time)
214  float GMRF_lambdaObsLoss; //!< The loss of information of the observations with each iteration
215 
216  bool GMRF_use_occupancy_information; //!< wether to use information of an occupancy_gridmap map for buidling the GMRF
217  std::string GMRF_simplemap_file; //!< simplemap_file name of the occupancy_gridmap
218  std::string GMRF_gridmap_image_file; //!< image name of the occupancy_gridmap
219  float GMRF_gridmap_image_res; //!< occupancy_gridmap resolution: size of each pixel (m)
220  size_t GMRF_gridmap_image_cx; //!< Pixel coordinates of the origin for the occupancy_gridmap
221  size_t GMRF_gridmap_image_cy; //!< Pixel coordinates of the origin for the occupancy_gridmap
222 
223  uint16_t GMRF_constraintsSize; //!< The size of the Gaussian window to impose fixed restrictions between cells.
224  float GMRF_constraintsSigma; //!< The sigma of the Gaussian window to impose fixed restrictions between cells.
225  /** @} */
226  };
227 
228  /** Changes the size of the grid, maintaining previous contents.
229  * \sa setSize
230  */
231  virtual void resize( float new_x_min,
232  float new_x_max,
233  float new_y_min,
234  float new_y_max,
235  const TRandomFieldCell& defaultValueNewCells,
236  float additionalMarginMeters = 1.0f );
237 
238  /** See docs in base class: in this class this always returns 0 */
240  const mrpt::maps::CMetricMap *otherMap,
241  const mrpt::poses::CPose3D &otherMapPose,
242  float maxDistForCorr = 0.10f,
243  float maxMahaDistForCorr = 2.0f
244  ) const;
245 
246 
247  /** The implementation in this class just calls all the corresponding method of the contained metric maps.
248  */
250  const std::string &filNamePrefix
251  ) const;
252 
253  /** Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the concentration of each cell.
254  * This method can only be called in a KF map model.
255  * \sa getAsMatlab3DGraphScript
256  */
257  virtual void saveAsMatlab3DGraph(const std::string &filName) const;
258 
259  /** Return a large text block with a MATLAB script to plot the contents of this map \sa saveAsMatlab3DGraph
260  * This method can only be called in a KF map model.
261  */
262  void getAsMatlab3DGraphScript(std::string &out_script) const;
263 
264  /** Returns a 3D object representing the map (mean).
265  */
266  virtual void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &outObj ) const;
267 
268  /** Returns two 3D objects representing the mean and variance maps.
269  */
270  virtual void getAs3DObject ( mrpt::opengl::CSetOfObjectsPtr &meanObj, mrpt::opengl::CSetOfObjectsPtr &varObj ) const;
271 
272  /** Return the type of the random-field grid map, according to parameters passed on construction.
273  */
275 
276  /** Direct update of the map with a reading in a given position of the map, using
277  * the appropriate method according to mapType passed in the constructor.
278  *
279  * This is a direct way to update the map, an alternative to the generic insertObservation() method which works with mrpt::obs::CObservation objects.
280  */
281  void insertIndividualReading(const float sensorReading,const mrpt::math::TPoint2D & point);
282 
283  /** Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form of the expected variance).
284  * This methods is implemented differently for the different gas map types.
285  */
286  virtual void predictMeasurement(
287  const double &x,
288  const double &y,
289  double &out_predict_response,
290  double &out_predict_response_variance );
291 
292  /** Return the mean and covariance vector of the full Kalman filter estimate (works for all KF-based methods). */
293  void getMeanAndCov( mrpt::math::CVectorDouble &out_means, mrpt::math::CMatrixDouble &out_cov) const;
294 
295  /** Return the mean and STD vectors of the full Kalman filter estimate (works for all KF-based methods). */
296  void getMeanAndSTD( mrpt::math::CVectorDouble &out_means, mrpt::math::CVectorDouble &out_STD) const;
297 
298  /** Load the mean and STD vectors of the full Kalman filter estimate (works for all KF-based methods). */
300 
301  protected:
302  /** Common options to all random-field grid maps: pointer that is set to the derived-class instance of "insertOptions" upon construction of this class. */
304 
305  /** Get the part of the options common to all CRandomFieldGridMap2D classes */
307 
308  /** The map representation type of this map, as passed in the constructor */
310 
311  mrpt::math::CMatrixD m_cov; //!< The whole covariance matrix, used for the Kalman Filter map representation.
312 
313  /** The compressed band diagonal matrix for the KF2 implementation.
314  * The format is a Nx(W^2+2W+1) matrix, one row per cell in the grid map with the
315  * cross-covariances between each cell and half of the window around it in the grid.
316  */
318  mutable bool m_hasToRecoverMeanAndCov; //!< Only for the KF2 implementation.
319 
320  /** @name Auxiliary vars for DM & DM+V methods
321  @{ */
323  std::vector<float> m_DM_gaussWindow;
326  /** @} */
327 
328  /** @name Auxiliary vars for GMRF method
329  @{ */
330 #if EIGEN_VERSION_AT_LEAST(3,1,0)
331  std::vector<Eigen::Triplet<double> > H_prior; // the prior part of H
332 #endif
333  Eigen::VectorXd g; // Gradient vector
334  size_t nPriorFactors; // L
335  size_t nObsFactors; // M
336  size_t nFactors; // L+M
337  std::multimap<size_t,size_t> cell_interconnections; //Store the interconnections (relations) of each cell with its neighbourds
338 
339  std::vector<float> gauss_val; // For factor Weigths (only for mrGMRF_G)
340 
342  {
343  float obsValue;
344  float Lambda;
345  bool time_invariant; //if the observation will lose weight (lambda) as time goes on (default false)
346  };
347 
348  std::vector<std::vector<TobservationGMRF> > activeObs; //Vector with the active observations and their respective Information
349 
350 
351  /** @} */
352 
353  /** The implementation of "insertObservation" for Achim Lilienthal's map models DM & DM+V.
354  * \param normReading Is a [0,1] normalized concentration reading.
355  * \param point Is the sensor location on the map
356  * \param is_DMV = false -> map type is Kernel DM; true -> map type is DM+V
357  */
359  float normReading,
360  const mrpt::math::TPoint2D &point,
361  bool is_DMV );
362 
363  /** The implementation of "insertObservation" for the (whole) Kalman Filter map model.
364  * \param normReading Is a [0,1] normalized concentration reading.
365  * \param point Is the sensor location on the map
366  */
368  float normReading,
369  const mrpt::math::TPoint2D &point );
370 
371  /** The implementation of "insertObservation" for the Efficient Kalman Filter map model.
372  * \param normReading Is a [0,1] normalized concentration reading.
373  * \param point Is the sensor location on the map
374  */
376  float normReading,
377  const mrpt::math::TPoint2D &point );
378 
379  /** The implementation of "insertObservation" for the Gaussian Markov Random Field map model.
380  * \param normReading Is a [0,1] normalized concentration reading.
381  * \param point Is the sensor location on the map
382  */
384  float normReading,
385  const mrpt::math::TPoint2D &point );
386 
387  /** solves the minimum quadratic system to determine the new concentration of each cell */
388  void updateMapEstimation_GMRF();
389 
390  /** Computes the confidence of the cell concentration (alpha) */
391  double computeConfidenceCellValue_DM_DMV (const TRandomFieldCell *cell ) const;
392 
393  /** Computes the average cell concentration, or the overall average value if it has never been observed */
394  double computeMeanCellValue_DM_DMV (const TRandomFieldCell *cell ) const;
395 
396  /** Computes the estimated variance of the cell concentration, or the overall average variance if it has never been observed */
397  double computeVarCellValue_DM_DMV (const TRandomFieldCell *cell ) const;
398 
399  /** In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std values.
400  * \sa m_hasToRecoverMeanAndCov
401  */
402  void recoverMeanAndCov() const;
403 
404  /** Erase all the contents of the map */
405  virtual void internal_clear();
406 
407  /** Check if two cells of the gridmap (m_map) are connected, based on the provided occupancy gridmap*/
409  const mrpt::maps::COccupancyGridMap2D *m_Ocgridmap,
410  size_t cxo_min,
411  size_t cxo_max,
412  size_t cyo_min,
413  size_t cyo_max,
414  const size_t seed_cxo,
415  const size_t seed_cyo,
416  const size_t objective_cxo,
417  const size_t objective_cyo);
418  };
420 
421 
422  } // End of namespace
423 
424 
425  // Specializations MUST occur at the same namespace:
426  namespace utils
427  {
428  template <>
429  struct TEnumTypeFiller<maps::CRandomFieldGridMap2D::TMapRepresentation>
430  {
432  static void fill(bimap<enum_t,std::string> &m_map)
433  {
434  m_map.insert(maps::CRandomFieldGridMap2D::mrKernelDM, "mrKernelDM");
435  m_map.insert(maps::CRandomFieldGridMap2D::mrKalmanFilter, "mrKalmanFilter");
436  m_map.insert(maps::CRandomFieldGridMap2D::mrKalmanApproximate, "mrKalmanApproximate");
437  m_map.insert(maps::CRandomFieldGridMap2D::mrKernelDMV, "mrKernelDMV");
441  }
442  };
443  } // End of namespace
444 } // End of namespace
445 
446 #endif
std::multimap< size_t, size_t > cell_interconnections
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:30
std::string GMRF_gridmap_image_file
image name of the occupancy_gridmap
CRandomFieldGridMap2D(TMapRepresentation mapType=mrAchim, float x_min=-2, float x_max=2, float y_min=-2, float y_max=2, float resolution=0.1)
Constructor.
void insertIndividualReading(const float sensorReading, const mrpt::math::TPoint2D &point)
Direct update of the map with a reading in a given position of the map, using the appropriate method ...
float sigma
The sigma of the "Parzen"-kernel Gaussian.
virtual void getAsBitmapFile(mrpt::utils::CImage &out_img) const
Returns an image just as described in saveAsBitmapFile.
void clear()
Calls the base CMetricMap::clear Declared here to avoid ambiguity between the two clear() in both bas...
TMapRepresentation
The type of map representation to be used, see CRandomFieldGridMap2D for a discussion.
This class is a "CSerializable" wrapper for "CMatrixTemplateNumeric".
Definition: CMatrixD.h:30
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, float maxDistForCorr=0.10f, float maxMahaDistForCorr=2.0f) const
See docs in base class: in this class this always returns 0.
float KF_defaultCellMeanValue
The default value for the mean of cells' concentration.
double computeConfidenceCellValue_DM_DMV(const TRandomFieldCell *cell) const
Computes the confidence of the cell concentration (alpha)
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:98
uint16_t GMRF_constraintsSize
The size of the Gaussian window to impose fixed restrictions between cells.
float GMRF_lambdaObsLoss
The loss of information of the observations with each iteration.
void clear()
Erase all the contents of the map.
void insertObservation_KF(float normReading, const mrpt::math::TPoint2D &point)
The implementation of "insertObservation" for the (whole) Kalman Filter map model.
mrpt::math::CMatrixD m_cov
The whole covariance matrix, used for the Kalman Filter map representation.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:51
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:70
mrpt::system::TTimeStamp last_updated
[Dynamic maps only] The timestamp of the last time the cell was updated
double gmrf_mean
[GMRF only] The mean value of this cell
Only specializations of this class are defined for each enum type of interest.
Definition: TEnumType.h:23
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const
The implementation in this class just calls all the corresponding method of the contained metric maps...
This class allows loading and storing values and vectors of different types from a configuration text...
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
This declaration must be inserted in virtual CSerializable classes definition:
double computeVarCellValue_DM_DMV(const TRandomFieldCell *cell) const
Computes the estimated variance of the cell concentration, or the overall average variance if it has ...
TMapRepresentation m_mapType
The map representation type of this map, as passed in the constructor.
void getAsMatlab3DGraphScript(std::string &out_script) const
Return a large text block with a MATLAB script to plot the contents of this map.
virtual void saveAsBitmapFile(const std::string &filName) const
Save the current map as a graphical file (BMP,PNG,...).
double dm_mean_w
[Kernel-methods only] The cumulative weights (concentration = alpha * dm_mean / dm_mean_w + (1-alpha)...
float KF_observationModelNoise
The sensor model noise (in normalized concentration units).
TInsertionOptionsCommon * m_insertOptions_common
Common options to all random-field grid maps: pointer that is set to the derived-class instance of "i...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
TRandomFieldCell(double kfmean_dm_mean=1e-20, double kfstd_dmmeanw=0)
Constructor.
A 2D grid of dynamic size which stores any kind of data at each cell.
Definition: CDynamicGrid.h:39
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
TMapRepresentation getMapType()
Return the type of the random-field grid map, according to parameters passed on construction.
double kf_mean
[KF-methods only] The mean value of this cell
void getMeanAndCov(mrpt::math::CVectorDouble &out_means, mrpt::math::CMatrixDouble &out_cov) const
Return the mean and covariance vector of the full Kalman filter estimate (works for all KF-based meth...
The contents of each cell in a CRandomFieldGridMap2D map.
virtual void saveAsMatlab3DGraph(const std::string &filName) const
Save a matlab ".m" file which represents as 3D surfaces the mean and a given confidence level for the...
void getMeanAndSTD(mrpt::math::CVectorDouble &out_means, mrpt::math::CVectorDouble &out_STD) const
Return the mean and STD vectors of the full Kalman filter estimate (works for all KF-based methods)...
A bidirectional version of std::map, declared as bimap and which actually contains two std...
Definition: bimap.h:27
void insertObservation_GMRF(float normReading, const mrpt::math::TPoint2D &point)
The implementation of "insertObservation" for the Gaussian Markov Random Field map model...
void recoverMeanAndCov() const
In the KF2 implementation, takes the auxiliary matrices and from them update the cells' mean and std ...
double dm_sigma_omega
[DM/DM+V methods] The scaling parameter for the confidence "alpha" values (see the IROS 2009 paper; s...
float GMRF_lambdaObs
The initial information (Lambda) of each observation (this information will decrease with time) ...
float cell2float(const TRandomFieldCell &c) const
bool m_hasToRecoverMeanAndCov
Only for the KF2 implementation.
float GMRF_gridmap_image_res
occupancy_gridmap resolution: size of each pixel (m)
double updated_std
[Dynamic maps only] The std cell value that was updated (to be used in the Forgetting_curve ...
virtual void resize(float new_x_min, float new_x_max, float new_y_min, float new_y_max, const TRandomFieldCell &defaultValueNewCells, float additionalMarginMeters=1.0f)
Changes the size of the grid, maintaining previous contents.
A class for storing an occupancy grid map.
float GMRF_lambdaPrior
The information (Lambda) of fixed map constraints.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property...
float KF_covSigma
The "sigma" for the initial covariance value between cells (in meters).
Declares a virtual base class for all metric maps storage classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:69
void insertObservation_KernelDM_DMV(float normReading, const mrpt::math::TPoint2D &point, bool is_DMV)
The implementation of "insertObservation" for Achim Lilienthal's map models DM & DM+V.
virtual void predictMeasurement(const double &x, const double &y, double &out_predict_response, double &out_predict_response_variance)
Returns the prediction of the measurement at some (x,y) coordinates, and its certainty (in the form o...
double dmv_var_mean
[Kernel DM-V only] The cumulative weighted variance of this cell
bool GMRF_use_occupancy_information
wether to use information of an occupancy_gridmap map for buidling the GMRF
std::string GMRF_simplemap_file
simplemap_file name of the occupancy_gridmap
uint16_t KF_W_size
[mrKalmanApproximate] The size of the window of neighbor cells.
float GMRF_constraintsSigma
The sigma of the Gaussian window to impose fixed restrictions between cells.
virtual void getAs3DObject(mrpt::opengl::CSetOfObjectsPtr &outObj) const
Returns a 3D object representing the map (mean).
void insertObservation_KF2(float normReading, const mrpt::math::TPoint2D &point)
The implementation of "insertObservation" for the Efficient Kalman Filter map model.
void setMeanAndSTD(mrpt::math::CVectorDouble &out_means, mrpt::math::CVectorDouble &out_STD)
Load the mean and STD vectors of the full Kalman filter estimate (works for all KF-based methods)...
mrpt::math::CMatrixD m_stackedCov
The compressed band diagonal matrix for the KF2 implementation.
virtual CRandomFieldGridMap2D::TInsertionOptionsCommon * getCommonInsertOptions()=0
Get the part of the options common to all CRandomFieldGridMap2D classes.
virtual void internal_clear()
Erase all the contents of the map.
bool exist_relation_between2cells(const mrpt::maps::COccupancyGridMap2D *m_Ocgridmap, size_t cxo_min, size_t cxo_max, size_t cyo_min, size_t cyo_max, const size_t seed_cxo, const size_t seed_cyo, const size_t objective_cxo, const size_t objective_cyo)
Check if two cells of the gridmap (m_map) are connected, based on the provided occupancy gridmap...
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
Definition: bimap.h:68
double dm_mean
[Kernel-methods only] The cumulative weighted readings of this cell
size_t GMRF_gridmap_image_cx
Pixel coordinates of the origin for the occupancy_gridmap.
virtual bool isEmpty() const
Returns true if the map is empty/no observation has been inserted (in this class it always return fal...
Another alias for "mrKernelDM", for backwards compatibility.
virtual ~CRandomFieldGridMap2D()
Destructor.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
Lightweight 2D point.
void updateMapEstimation_GMRF()
solves the minimum quadratic system to determine the new concentration of each cell ...
float KF_initialCellStd
The initial standard deviation of each cell's concentration (will be stored both at each cell's struc...
size_t GMRF_gridmap_image_cy
Pixel coordinates of the origin for the occupancy_gridmap.
utils::CDynamicGrid< TRandomFieldCell > BASE
double kf_std
[KF-methods only] The standard deviation value of this cell
double computeMeanCellValue_DM_DMV(const TRandomFieldCell *cell) const
Computes the average cell concentration, or the overall average value if it has never been observed...
std::vector< std::vector< TobservationGMRF > > activeObs



Page generated by Doxygen 1.8.9.1 for MRPT 1.3.0 SVN: at Sun Sep 13 03:55:12 UTC 2015