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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020