MRPT  2.0.4
data_association_unittest.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include <gtest/gtest.h>
12 
13 using namespace mrpt;
14 using namespace mrpt::slam;
15 using namespace mrpt::math;
16 using namespace std;
17 
18 TEST(DataAssociation, TestNoICs)
19 {
20  // Try to do DA when no individual compatible pairings exist.
21  // Based on test proposed by Mauricio Soto Alvarez:
22  // See:
23  // https://sourceforge.net/tracker/?func=detail&aid=3562885&group_id=205280&atid=993006
24 
25  CMatrixDouble y, y_cov, z;
26  y.setSize(1, 1);
27  y_cov.setSize(1, 1);
28  z.setSize(1, 1);
29 
30  y(0, 0) = 0.0;
31  y_cov(0, 0) = 1.0;
32  z(0, 0) = 10.0;
33 
34  const TDataAssociationMethod dams[2] = {assocNN, assocJCBB};
35  const TDataAssociationMetric damets[2] = {metricMaha, metricML};
36 
37  for (unsigned int da_metric = 0;
38  da_metric < sizeof(damets) / sizeof(damets[0]); ++da_metric)
39  {
40  const TDataAssociationMetric damet = damets[da_metric];
41 
42  for (unsigned int da_method = 0;
43  da_method < sizeof(dams) / sizeof(dams[0]); ++da_method)
44  {
45  const TDataAssociationMethod dam = dams[da_method];
46 
47  TDataAssociationResults DAresults;
49  z, y, y_cov, DAresults, dam, damet, 0.99, true,
50  std::vector<prediction_index_t>(), metricMaha, 0.0);
51 
52  EXPECT_EQ(0u, DAresults.associations.size())
53  << "For da_method=" << da_method
54  << " and da_metric=" << da_metric << endl;
55  }
56  }
57 }
Nearest-neighbor.
Mahalanobis distance.
STL namespace.
JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001].
This base provides a set of functions for maths stuff.
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
TEST(DataAssociation, TestNoICs)
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...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
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...
void setSize(size_t row, size_t col, bool zeroNewElements=false)
Changes the size of matrix, maintaining the previous contents.
EXPECT_EQ(out.image_pair_was_used.size(), NUM_IMGS)
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.



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