Main MRPT website > C++ reference for MRPT 1.9.9
data_association.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "slam-precomp.h" // Precompiled headers
11 
12 /*
13  For all data association algorithms, the individual compatibility is
14  estabished by
15  the chi2 test (Mahalanobis distance), but later on one of the potential
16  pairings is
17  picked by the metric given by the user (maha vs. match. lik.)
18 
19  Related papers:
20  - Matching likelihood. See: http://www.mrpt.org/Paper:Matching_Likelihood
21 
22  - JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]
23 
24 */
25 
27 #include <mrpt/math/distributions.h> // for chi2inv
28 #include <mrpt/math/data_utils.h>
31 
32 #include <set>
33 #include <numeric> // accumulate
34 #include <memory> // unique_ptr
35 
36 #include <mrpt/otherlibs/nanoflann/nanoflann.hpp> // For kd-tree's
37 #include <mrpt/math/KDTreeCapable.h> // For kd-tree's
38 
39 using namespace std;
40 using namespace mrpt;
41 using namespace mrpt::math;
42 using namespace mrpt::poses;
43 using namespace mrpt::slam;
44 using namespace mrpt::utils;
45 
46 namespace mrpt
47 {
48 namespace slam
49 {
51 {
52  /** Just to avoid recomputing them all the time. */
53  size_t nPredictions, nObservations, length_O;
54  std::map<size_t, size_t> currentAssociation;
55 };
56 
57 /** Computes the joint distance metric (mahalanobis or matching likelihood)
58  * between two a set of associations
59  *
60  * On "currentAssociation": maps "ID_obs" -> "ID_pred"
61  * For each landmark ID in the observations (ID_obs), its association
62  * in the predictions, that is: ID_pred = associations[ID_obs]
63  *
64  */
65 template <typename T, TDataAssociationMetric METRIC>
67  const CMatrixTemplateNumeric<T>& Z_observations_mean,
68  const CMatrixTemplateNumeric<T>& Y_predictions_mean,
69  const CMatrixTemplateNumeric<T>& Y_predictions_cov,
70  const TAuxDataRecursiveJCBB& info, const TDataAssociationResults& aux_data)
71 {
72  MRPT_UNUSED_PARAM(aux_data);
73  // Make a list of the indices of the predictions that appear in
74  // "currentAssociation":
75  const size_t N = info.currentAssociation.size();
76  ASSERT_(N > 0)
77 
78  vector_size_t indices_pred(N); // Appearance order indices in the std::maps
79  vector_size_t indices_obs(N);
80 
81  {
82  size_t i = 0;
84  info.currentAssociation.begin();
85  it != info.currentAssociation.end(); ++it)
86  {
87  indices_obs[i] = it->first;
88  indices_pred[i] = it->second;
89  i++;
90  }
91  }
92 
93  // ----------------------------------------------------------------------
94  // Extract submatrix of the covariances involved here:
95  // COV = PREDICTIONS_COV(INDX,INDX) + OBSERVATIONS_COV(INDX2,INDX2)
96  // ----------------------------------------------------------------------
97  Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> COV;
98  Y_predictions_cov.extractSubmatrixSymmetricalBlocks(
99  info.length_O, // dims of cov. submatrices
100  indices_pred, COV);
101 
102  // ----------------------------------------------------------------------
103  // Mean:
104  // The same for the vector of "errors" or "innovation" between predictions
105  // and observations:
106  // ----------------------------------------------------------------------
107  Eigen::Matrix<T, Eigen::Dynamic, 1> innovations(N * info.length_O);
108  T* dst_ptr = &innovations[0];
110  info.currentAssociation.begin();
111  it != info.currentAssociation.end(); ++it)
112  {
113  const T* pred_i_mean = Y_predictions_mean.get_unsafe_row(it->second);
114  const T* obs_i_mean = Z_observations_mean.get_unsafe_row(it->first);
115 
116  for (unsigned int k = 0; k < info.length_O; k++)
117  *dst_ptr++ = pred_i_mean[k] - obs_i_mean[k];
118  }
119 
120  // Compute mahalanobis distance squared:
122  COV.inv_fast(COV_inv);
123 
124  const double d2 = mrpt::math::multiply_HCHt_scalar(innovations, COV_inv);
125 
126  if (METRIC == metricMaha) return d2;
127 
128  ASSERT_(METRIC == metricML);
129 
130  // Matching likelihood: The evaluation at 0 of the PDF of the difference
131  // between the two Gaussians:
132  const T cov_det = COV.det();
133  const double ml = exp(-0.5 * d2) / (std::pow(M_2PI, info.length_O * 0.5) *
134  std::sqrt(cov_det));
135  return ml;
136 }
137 
138 template <TDataAssociationMetric METRIC>
139 bool isCloser(const double v1, const double v2);
140 
141 template <>
142 bool isCloser<metricMaha>(const double v1, const double v2)
143 {
144  return v1 < v2;
145 }
146 
147 template <>
148 bool isCloser<metricML>(const double v1, const double v2)
149 {
150  return v1 > v2;
151 }
152 
153 /* Based on MATLAB code by:
154  University of Zaragoza
155  Centro Politecnico Superior
156  Robotics and Real Time Group
157  Authors of the original MATLAB code: J. Neira, J. Tardos
158  C++ version: J.L. Blanco Claraco
159 */
160 template <typename T, TDataAssociationMetric METRIC>
162  const mrpt::math::CMatrixTemplateNumeric<T>& Z_observations_mean,
163  const mrpt::math::CMatrixTemplateNumeric<T>& Y_predictions_mean,
164  const mrpt::math::CMatrixTemplateNumeric<T>& Y_predictions_cov,
165  TDataAssociationResults& results, const TAuxDataRecursiveJCBB& info,
166  const observation_index_t curObsIdx)
167 {
168  // End of iteration?
169  if (curObsIdx >= info.nObservations)
170  {
171  if (info.currentAssociation.size() > results.associations.size())
172  {
173  // It's a better choice since more features are matched.
174  results.associations = info.currentAssociation;
175  results.distance = joint_pdf_metric<T, METRIC>(
176  Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
177  info, results);
178  }
179  else if (
180  !info.currentAssociation.empty() &&
181  info.currentAssociation.size() == results.associations.size())
182  {
183  // The same # of features matched than the previous best one...
184  // decide by better distance:
185  const double d2 = joint_pdf_metric<T, METRIC>(
186  Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
187  info, results);
188 
189  if (isCloser<METRIC>(d2, results.distance))
190  {
191  results.associations = info.currentAssociation;
192  results.distance = d2;
193  }
194  }
195  }
196  else // A normal iteration:
197  {
198  // Iterate for all compatible landmarsk of "curObsIdx"
199  const observation_index_t obsIdx = curObsIdx;
200 
201  const size_t nPreds = results.indiv_compatibility.getRowCount();
202 
203  // Can we do it better than the current "results.associations"?
204  // This can be checked by counting the potential new pairings+the so-far
205  // established ones.
206  // Matlab: potentials = pairings(compatibility.AL(i+1:end))
207  // Moved up by Kasra Khosoussi
208  const size_t potentials = std::accumulate(
209  results.indiv_compatibility_counts.begin() + (obsIdx + 1),
210  results.indiv_compatibility_counts.end(), 0);
211  for (prediction_index_t predIdx = 0; predIdx < nPreds; predIdx++)
212  {
213  if ((info.currentAssociation.size() + potentials) >=
214  results.associations.size())
215  {
216  // Only if predIdx is NOT already assigned:
217  if (results.indiv_compatibility(predIdx, obsIdx))
218  {
219  // Only if predIdx is NOT already assigned:
220  bool already_asigned = false;
222  info.currentAssociation.begin();
223  itS != info.currentAssociation.end(); ++itS)
224  {
225  if (itS->second == predIdx)
226  {
227  already_asigned = true;
228  break;
229  }
230  }
231 
232  if (!already_asigned)
233  {
234  // Launch a new recursive line for this hipothesis:
235  TAuxDataRecursiveJCBB new_info = info;
236  new_info.currentAssociation[curObsIdx] = predIdx;
237 
238  results.nNodesExploredInJCBB++;
239 
240  JCBB_recursive<T, METRIC>(
241  Z_observations_mean, Y_predictions_mean,
242  Y_predictions_cov, results, new_info,
243  curObsIdx + 1);
244  }
245  }
246  }
247  }
248 
249  // Can we do it better than the current "results.associations"?
250  if ((info.currentAssociation.size() + potentials) >=
251  results.associations.size())
252  {
253  // Yes we can </obama>
254 
255  // star node: Ei not paired
256  results.nNodesExploredInJCBB++;
257  JCBB_recursive<T, METRIC>(
258  Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
259  results, info, curObsIdx + 1);
260  }
261  }
262 }
263 
264 } // end namespace
265 } // end namespace
266 
267 /* ==================================================================================================
268 Computes the data-association between the prediction of a set of landmarks and
269 their observations, all of them with covariance matrices.
270 * Implemented methods include (see TDataAssociation)
271 * - NN: Nearest-neighbor
272 * - JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]
273 *
274 * With both a Mahalanobis-distance or Matching-likelihood metric (See paper:
275 http://www.mrpt.org/Paper:Matching_Likelihood )
276 *
277 * \param Z_observations_mean [IN] An MxO matrix with the M observations, each
278 row containing the observation "mean".
279 * \param Y_predictions_mean [IN ] An NxO matrix with the N predictions, each row
280 containing the mean of one prediction.
281 * \param Y_predictions_cov [IN ] An N·OxN·O matrix with the full covariance
282 matrix of all the N predictions.
283 
284 * \param predictions_mean [IN] The list of predicted locations of
285 landmarks/features, indexed by their ID. The 2D/3D locations are in the same
286 coordinate framework than "observations".
287 * \param predictions_cov [IN] The full covariance matrix of predictions, in
288 blocks of 2x2 matrices. The order of the submatrices is the appearance order of
289 lanmarks in "predictions_mean".
290 * \param results [OUT] The output data association hypothesis, and other useful
291 information.
292 * \param method [IN, optional] The selected method to make the associations.
293 * \param chi2quantile [IN, optional] The threshold for considering a match
294 between two close Gaussians for two landmarks, in the range [0,1]. It is used to
295 call mrpt::math::chi2inv
296 * \param use_kd_tree [IN, optional] Build a KD-tree to speed-up the evaluation
297 of individual compatibility (IC). It's perhaps more efficient to disable it for
298 a small number of features. (default=true).
299 * \param predictions_IDs [IN, optional] (default:none) An N-vector. If provided,
300 the resulting associations in "results.associations" will not contain prediction
301 indices "i", but "predictions_IDs[i]".
302 *
303  ==================================================================================================
304 */
306  const mrpt::math::CMatrixDouble& Z_observations_mean,
307  const mrpt::math::CMatrixDouble& Y_predictions_mean,
308  const mrpt::math::CMatrixDouble& Y_predictions_cov,
309  TDataAssociationResults& results, const TDataAssociationMethod method,
310  const TDataAssociationMetric metric, const double chi2quantile,
311  const bool DAT_ASOC_USE_KDTREE,
312  const std::vector<prediction_index_t>& predictions_IDs,
313  const TDataAssociationMetric compatibilityTestMetric,
314  const double log_ML_compat_test_threshold)
315 {
316  // For details on the theory, see the papers cited at the beginning of this
317  // file.
318 
319  using nanoflann::KDTreeEigenMatrixAdaptor;
320 
321  MRPT_START
322 
323  results.clear();
324 
325  const size_t nPredictions = size(Y_predictions_mean, 1);
326  const size_t nObservations = size(Z_observations_mean, 1);
327 
328  const size_t length_O = size(Z_observations_mean, 2);
329 
330  ASSERT_(nPredictions != 0)
331  ASSERT_(nObservations != 0)
332  ASSERT_(length_O == size(Y_predictions_mean, 2))
333  ASSERT_(length_O * nPredictions == size(Y_predictions_cov, 1))
334  ASSERT_(Y_predictions_cov.isSquare())
335 
336  ASSERT_(chi2quantile > 0 && chi2quantile < 1)
337  ASSERT_(metric == metricMaha || metric == metricML)
338 
339  const double chi2thres = mrpt::math::chi2inv(chi2quantile, length_O);
340 
341  // ------------------------------------------------------------
342  // Build a KD-tree of the predictions for quick look-up:
343  // ------------------------------------------------------------
344  typedef std::unique_ptr<KDTreeEigenMatrixAdaptor<CMatrixDouble>>
345  KDTreeMatrixPtr;
346  KDTreeMatrixPtr kd_tree;
347  const size_t N_KD_RESULTS = nPredictions;
348  std::vector<double> kd_result_distances(
349  DAT_ASOC_USE_KDTREE ? N_KD_RESULTS : 0);
350  std::vector<CMatrixDouble::Index> kd_result_indices(
351  DAT_ASOC_USE_KDTREE ? N_KD_RESULTS : 0);
352  std::vector<double> kd_queryPoint(DAT_ASOC_USE_KDTREE ? length_O : 0);
353 
354  if (DAT_ASOC_USE_KDTREE)
355  {
356  // Construct kd-tree for the predictions:
357  kd_tree = KDTreeMatrixPtr(
358  new KDTreeEigenMatrixAdaptor<CMatrixDouble>(
359  length_O, Y_predictions_mean));
360  }
361 
362  // Initialize with the worst possible distance:
363  results.distance =
364  (metric == metricML) ? 0 : std::numeric_limits<double>::max();
365 
366  //-------------------------------------------
367  // Compute the individual compatibility:
368  //-------------------------------------------
369  results.indiv_distances.resize(nPredictions, nObservations);
370  results.indiv_compatibility.setSize(nPredictions, nObservations);
371  results.indiv_compatibility_counts.assign(nObservations, 0);
372 
373  results.indiv_distances.fill(
374  metric == metricMaha ? 1000 /*A very large Sq. Maha. Dist. */
375  : -1000 /*A very small log-likelihoo */);
376  results.indiv_compatibility.fillAll(false);
377 
378  CMatrixDouble pred_i_cov(length_O, length_O);
379 
380  Eigen::VectorXd diff_means_i_j(length_O);
381 
382  for (size_t j = 0; j < nObservations; ++j)
383  {
384  if (!DAT_ASOC_USE_KDTREE)
385  {
386  // Compute all the distances w/o a KD-tree
387  for (size_t i = 0; i < nPredictions; ++i)
388  {
389  // Evaluate sqr. mahalanobis distance of obs_j -> pred_i:
390  const size_t pred_cov_idx =
391  i * length_O; // Extract the submatrix from the diagonal:
392  Y_predictions_cov.extractMatrix(
393  pred_cov_idx, pred_cov_idx, length_O, length_O, pred_i_cov);
394 
395  for (size_t k = 0; k < length_O; k++)
396  diff_means_i_j[k] = Z_observations_mean.get_unsafe(j, k) -
397  Y_predictions_mean.get_unsafe(i, k);
398 
399  double d2, ml;
400  // mrpt::math::productIntegralAndMahalanobisTwoGaussians(diff_means_i_j,pred_i_cov,obs_j_cov,
401  // d2,ml);
403  diff_means_i_j, pred_i_cov, d2, ml);
404 
405  // The distance according to the metric
406  double val = (metric == metricMaha) ? d2 : ml;
407 
408  results.indiv_distances(i, j) = val;
409 
410  // Individual compatibility
411  const bool IC = (compatibilityTestMetric == metricML)
412  ? (ml > log_ML_compat_test_threshold)
413  : (d2 < chi2thres);
414  results.indiv_compatibility(i, j) = IC;
415  if (IC) results.indiv_compatibility_counts[j]++;
416  }
417  }
418  else
419  {
420  // Use a kd-tree and compute only the N closest ones:
421  for (size_t k = 0; k < length_O; k++)
422  kd_queryPoint[k] = Z_observations_mean.get_unsafe(j, k);
423 
424  kd_tree->query(
425  &kd_queryPoint[0], N_KD_RESULTS, &kd_result_indices[0],
426  &kd_result_distances[0]);
427 
428  // Only compute the distances for these ones:
429  for (size_t w = 0; w < N_KD_RESULTS; w++)
430  {
431  const size_t i = kd_result_indices[w]; // This is the index of
432  // the prediction in
433  // "predictions_mean"
434 
435  // Build the PDF of the prediction:
436  const size_t pred_cov_idx =
437  i * length_O; // Extract the submatrix from the diagonal:
438  Y_predictions_cov.extractMatrix(
439  pred_cov_idx, pred_cov_idx, length_O, length_O, pred_i_cov);
440 
441  for (size_t k = 0; k < length_O; k++)
442  diff_means_i_j[k] = Z_observations_mean.get_unsafe(j, k) -
443  Y_predictions_mean.get_unsafe(i, k);
444 
445  double d2, ml;
446  // mrpt::math::productIntegralAndMahalanobisTwoGaussians(diff_means_i_j,pred_i_cov,obs_j_cov,
447  // d2,ml);
449  diff_means_i_j, pred_i_cov, d2, ml);
450 
451  if (d2 > 6 * chi2thres)
452  break; // Since kd-tree returns the landmarks by distance
453  // order, we can skip the rest
454 
455  // The distance according to the metric
456  double val = (metric == metricMaha) ? d2 : ml;
457 
458  results.indiv_distances(i, j) = val;
459 
460  // Individual compatibility
461  const bool IC = (compatibilityTestMetric == metricML)
462  ? (ml > log_ML_compat_test_threshold)
463  : (d2 < chi2thres);
464  results.indiv_compatibility(i, j) = IC;
465  if (IC) results.indiv_compatibility_counts[j]++;
466  }
467  } // end use KD-Tree
468  } // end for
469 
470 #if 0
471  cout << "Distances: " << endl << results.indiv_distances << endl;
472  //cout << "indiv compat: " << endl << results.indiv_compatibility << endl;
473 #endif
474 
475  // Do associations:
476  results.associations.clear();
477 
478  switch (method)
479  {
480  // --------------------------
481  // Nearest-neighbor
482  // --------------------------
483  case assocNN:
484  {
485  // 1) For each observation "j", make a list of the indiv. compatible
486  // predictions and their distances, sorted first the best.
487  // NOTE: distances are saved so smaller is always better,
488  // hence "metricML" are made negative.
489  // -------------------------------------------------------------------
490  typedef multimap<double, pair<observation_index_t,
491  multimap<double, prediction_index_t>>>
492  TListAllICs;
493  TListAllICs lst_all_ICs;
494 
495  for (observation_index_t j = 0; j < nObservations; ++j)
496  {
497  multimap<double, prediction_index_t> ICs;
498 
499  for (prediction_index_t i = 0; i < nPredictions; ++i)
500  {
501  if (results.indiv_compatibility.get_unsafe(i, j))
502  {
503  double d2 = results.indiv_distances.get_unsafe(i, j);
504  if (metric == metricML) d2 = -d2;
505  ICs.insert(make_pair(d2, i));
506  }
507  }
508 
509  if (!ICs.empty())
510  {
511  const double best_dist = ICs.begin()->first;
512  lst_all_ICs.insert(make_pair(best_dist, make_pair(j, ICs)));
513  }
514  }
515 
516  // 2) With that lists, start by the best one and make the
517  // assignment.
518  // Remove the prediction from the list of available, and go on.
519  // --------------------------------------------------------------------
520  std::set<prediction_index_t> lst_already_taken_preds;
521 
522  for (TListAllICs::const_iterator it = lst_all_ICs.begin();
523  it != lst_all_ICs.end(); ++it)
524  {
525  const observation_index_t obs_id = it->second.first;
526  const multimap<double, prediction_index_t>& lstCompats =
527  it->second.second;
528 
530  lstCompats.begin();
531  itP != lstCompats.end(); ++itP)
532  {
533  if (lst_already_taken_preds.find(itP->second) ==
534  lst_already_taken_preds.end())
535  {
536  // It's free: make the association:
537  results.associations[obs_id] = itP->second;
538  lst_already_taken_preds.insert(itP->second);
539  break;
540  }
541  }
542  }
543  }
544  break;
545 
546  // ------------------------------------
547  // Joint Compatibility Branch & Bound:
548  // ------------------------------------
549  case assocJCBB:
550  {
551  // Call to the recursive method:
553  info.nPredictions = nPredictions;
554  info.nObservations = nObservations;
555  info.length_O = length_O;
556 
557  if (metric == metricMaha)
558  JCBB_recursive<CMatrixDouble::Scalar, metricMaha>(
559  Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
560  results, info, 0);
561  else
562  JCBB_recursive<CMatrixDouble::Scalar, metricML>(
563  Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
564  results, info, 0);
565  }
566  break;
567 
568  default:
569  THROW_EXCEPTION("Unknown value of 'method'")
570  };
571 
572  // If a mapping of prediction indices to IDs was providen, apply it now:
573  // ------------------------------------------------------------------------
574  if (!predictions_IDs.empty())
575  {
576  ASSERT_(predictions_IDs.size() == nPredictions);
578  results.associations.begin();
579  itAssoc != results.associations.end(); ++itAssoc)
580  itAssoc->second = predictions_IDs[itAssoc->second];
581  }
582 
583  MRPT_END
584 }
585 
586 /* ==================================================================================================
587  data_association_independent_predictions
588  ==================================================================================================
589  */
591  const mrpt::math::CMatrixDouble& Z_observations_mean,
592  const mrpt::math::CMatrixDouble& Y_predictions_mean,
593  const mrpt::math::CMatrixDouble& Y_predictions_cov_stacked,
594  TDataAssociationResults& results, const TDataAssociationMethod method,
595  const TDataAssociationMetric metric, const double chi2quantile,
596  const bool DAT_ASOC_USE_KDTREE,
597  const std::vector<prediction_index_t>& predictions_IDs,
598  const TDataAssociationMetric compatibilityTestMetric,
599  const double log_ML_compat_test_threshold)
600 {
601  MRPT_START
602 
603  results.clear();
604 
605  const size_t nPredictions = size(Y_predictions_mean, 1);
606  const size_t nObservations = size(Z_observations_mean, 1);
607 
608  const size_t length_O = size(Z_observations_mean, 2);
609 
610  ASSERT_(nPredictions != 0)
611  ASSERT_(nObservations != 0)
612  ASSERT_(length_O == size(Y_predictions_mean, 2))
613  ASSERT_(length_O * nPredictions == size(Y_predictions_cov_stacked, 1))
614 
615  ASSERT_(chi2quantile > 0 && chi2quantile < 1)
616  ASSERT_(metric == metricMaha || metric == metricML)
617 
618  // const double chi2thres = mrpt::math::chi2inv( chi2quantile, length_O );
619 
620  // TODO: Optimized version!!
621  CMatrixDouble Y_predictions_cov_full(
622  length_O * nPredictions, length_O * nPredictions);
623  CMatrixDouble COV_i(length_O, length_O);
624  for (size_t i = 0; i < nPredictions; i++)
625  {
626  const size_t idx = i * length_O;
627  Y_predictions_cov_stacked.extractSubmatrix(
628  idx, idx + length_O - 1, 0, length_O - 1, COV_i);
629  Y_predictions_cov_full.insertMatrix(idx, idx, COV_i);
630  }
631 
633  Z_observations_mean, Y_predictions_mean, Y_predictions_cov_full,
634  results, method, metric, chi2quantile, DAT_ASOC_USE_KDTREE,
635  predictions_IDs, compatibilityTestMetric, log_ML_compat_test_threshold);
636 
637  MRPT_END
638 }
bool isCloser< metricML >(const double v1, const double v2)
const T & get_unsafe(size_t row, size_t col) const
Fast but unsafe method to read a value from the matrix.
Nearest-neighbor.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Mahalanobis distance.
size_t observation_index_t
Used in mrpt::slam::TDataAssociationResults.
vector_uint indiv_compatibility_counts
The sum of each column of indiv_compatibility, that is, the number of compatible pairings for each ob...
#define THROW_EXCEPTION(msg)
Scalar * iterator
Definition: eigen_plugins.h:26
mrpt::math::CMatrixDouble indiv_distances
Individual mahalanobis distances (or matching likelihood, depending on the selected metric) between p...
MAT_C::Scalar multiply_HCHt_scalar(const VECTOR_H &H, const MAT_C &C)
r (a scalar) = H * C * H^t (with a vector H and a symmetric matrix C)
Definition: ops_matrices.h:69
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
void JCBB_recursive(const mrpt::math::CMatrixTemplateNumeric< T > &Z_observations_mean, const mrpt::math::CMatrixTemplateNumeric< T > &Y_predictions_mean, const mrpt::math::CMatrixTemplateNumeric< T > &Y_predictions_cov, TDataAssociationResults &results, const TAuxDataRecursiveJCBB &info, const observation_index_t curObsIdx)
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
size_t nPredictions
Just to avoid recomputing them all the time.
#define M_2PI
Definition: mrpt_macros.h:437
bool isCloser< metricMaha >(const double v1, const double v2)
JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001].
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
double distance
The Joint Mahalanobis distance or matching likelihood of the best associations found.
void mahalanobisDistance2AndLogPDF(const VECLIKE &diff_mean, const MATRIXLIKE &cov, T &maha2_out, T &log_pdf_out)
Computes both, the logarithm of the PDF and the square Mahalanobis distance between a point (given by...
Definition: data_utils.h:212
#define MRPT_END
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
int val
Definition: mrpt_jpeglib.h:955
std::map< size_t, size_t > currentAssociation
mrpt::math::CMatrixBool indiv_compatibility
The result of a chi2 test for compatibility using mahalanobis distance - Indices are like in "indiv_d...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
void data_association_independent_predictions(const mrpt::math::CMatrixDouble &Z_observations_mean, const mrpt::math::CMatrixDouble &Y_predictions_mean, const mrpt::math::CMatrixDouble &Y_predictions_cov, TDataAssociationResults &results, const TDataAssociationMethod method=assocJCBB, const TDataAssociationMetric metric=metricMaha, const double chi2quantile=0.99, const bool DAT_ASOC_USE_KDTREE=true, const std::vector< prediction_index_t > &predictions_IDs=std::vector< prediction_index_t >(), const TDataAssociationMetric compatibilityTestMetric=metricMaha, const double log_ML_compat_test_threshold=0.0)
Computes the data-association between the prediction of a set of landmarks and their observations...
double joint_pdf_metric(const CMatrixTemplateNumeric< T > &Z_observations_mean, const CMatrixTemplateNumeric< T > &Y_predictions_mean, const CMatrixTemplateNumeric< T > &Y_predictions_cov, const TAuxDataRecursiveJCBB &info, const TDataAssociationResults &aux_data)
Computes the joint distance metric (mahalanobis or matching likelihood) between two a set of associat...
#define MRPT_START
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double chi2inv(double P, unsigned int dim=1)
The "quantile" of the Chi-Square distribution, for dimension "dim" and probability 0<P<1 (the inverse...
Definition: math.cpp:998
GLfloat GLfloat v1
Definition: glext.h:4105
std::map< observation_index_t, prediction_index_t > associations
For each observation (with row index IDX_obs in the input "Z_observations"), its association in the p...
#define ASSERT_(f)
size_t getRowCount() const
Number of rows in the matrix.
size_t prediction_index_t
Used in mrpt::slam::TDataAssociationResults.
std::vector< size_t > vector_size_t
Definition: types_simple.h:26
void setSize(size_t row, size_t col, bool zeroNewElements=false)
Changes the size of matrix, maintaining the previous contents.
size_t nNodesExploredInJCBB
Only for the JCBB method,the number of recursive calls expent in the algorithm.
GLfloat GLfloat GLfloat v2
Definition: glext.h:4107
GLsizeiptr size
Definition: glext.h:3923
The results from mrpt::slam::data_association.
Matching likelihood (See TDataAssociationMetric for a paper explaining this metric) ...
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
bool isCloser(const double v1, const double v2)
void data_association_full_covariance(const mrpt::math::CMatrixDouble &Z_observations_mean, const mrpt::math::CMatrixDouble &Y_predictions_mean, const mrpt::math::CMatrixDouble &Y_predictions_cov, TDataAssociationResults &results, const TDataAssociationMethod method=assocJCBB, const TDataAssociationMetric metric=metricMaha, const double chi2quantile=0.99, const bool DAT_ASOC_USE_KDTREE=true, const std::vector< prediction_index_t > &predictions_IDs=std::vector< prediction_index_t >(), const TDataAssociationMetric compatibilityTestMetric=metricMaha, const double log_ML_compat_test_threshold=0.0)
Computes the data-association between the prediction of a set of landmarks and their observations...
void fillAll(const T &val)



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019