MRPT  1.9.9
data_association.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 data_association_H
10 #define data_association_H
11 
14 #include <mrpt/math/CMatrixTemplate.h> // mrpt::math::CMatrixBool
16 
17 namespace mrpt::slam
18 {
19 /** \addtogroup data_assoc_grp Data association
20  * \ingroup mrpt_slam_grp
21  * @{ */
22 
23 /** @name Data association
24  @{
25  */
26 
27 /** Different algorithms for data association, used in
28  * mrpt::slam::data_association
29  */
31 {
32  /** Nearest-neighbor. */
33  assocNN = 0,
34  /** JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]. */
36 };
37 
38 /** Different metrics for data association, used in mrpt::slam::data_association
39  * For a comparison of both methods see paper:
40  * * J.L. Blanco, J. Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "An
41  * alternative to the Mahalanobis distance for determining optimal
42  * correspondences in data association", IEEE Transactions on Robotics (T-RO),
43  * (2012) DOI: 10.1109/TRO.2012.2193706 Draft:
44  * http://ingmec.ual.es/~jlblanco/papers/blanco2012amd.pdf
45  */
47 {
48  /** Mahalanobis distance */
50  /** Matching likelihood (See TDataAssociationMetric for a paper explaining
51  this metric) */
53 };
54 
55 /** Used in mrpt::slam::TDataAssociationResults */
56 using observation_index_t = size_t;
57 /** Used in mrpt::slam::TDataAssociationResults */
58 using prediction_index_t = size_t;
59 
60 /** The results from mrpt::slam::data_association
61  */
63 {
65  : associations(),
66  distance(0),
67  indiv_distances(0, 0),
68  indiv_compatibility(0, 0),
71  {
72  }
73 
74  void clear()
75  {
76  associations.clear();
77  distance = 0;
78  indiv_distances.setSize(0, 0);
82  }
83 
84  /** For each observation (with row index IDX_obs in the input
85  * "Z_observations"), its association in the predictions, as the row index
86  * in the "Y_predictions_mean" input (or it's mapping to a custom ID, if it
87  * was provided).
88  * Note that not all observations may have an associated prediction.
89  * An observation with index "IDX_obs" corresponds to the prediction number
90  * "associations[IDX_obs]", or it may not correspond to anyone if it's not
91  * present
92  * in the std::map (Tip: Use
93  * associations.find(IDX_obs)!=associations.end() )
94  * \note The types observation_index_t and prediction_index_t are just used
95  * for clarity, use normal size_t's.
96  */
97  std::map<observation_index_t, prediction_index_t> associations;
98  /** The Joint Mahalanobis distance or matching likelihood of the best
99  * associations found. */
100  double distance;
101 
102  /** Individual mahalanobis distances (or matching likelihood, depending on
103  * the selected metric) between predictions (row indices) & observations
104  * (column indices).
105  * Indices are for the appearing order in the arguments
106  * "Y_predictions_mean" & "Z_observations", they are NOT landmark IDs.
107  */
109  /** The result of a chi2 test for compatibility using mahalanobis distance -
110  * Indices are like in "indiv_distances". */
112  /** The sum of each column of indiv_compatibility, that is, the number of
113  * compatible pairings for each observation. */
114  std::vector<uint32_t> indiv_compatibility_counts;
115 
116  /** Only for the JCBB method,the number of recursive calls expent in the
117  * algorithm. */
119 };
120 
121 /** Computes the data-association between the prediction of a set of landmarks
122  *and their observations, all of them with covariance matrices - Generic
123  *version with prediction full cross-covariances.
124  * Implemented methods include (see TDataAssociation)
125  * - NN: Nearest-neighbor
126  * - JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]
127  *
128  * With both a Mahalanobis-distance or Matching-likelihood metric. For a
129  *comparison of both methods, see paper:
130  * * J.L. Blanco, J. Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "An
131  *alternative to the Mahalanobis distance for determining optimal
132  *correspondences in data association", IEEE Transactions on Robotics (T-RO),
133  *(2012) DOI: 10.1109/TRO.2012.2193706 Draft:
134  *http://ingmec.ual.es/~jlblanco/papers/blanco2012amd.pdf
135  *
136  * \param Z_observations_mean [IN] An MxO matrix with the M observations, each
137  *row containing the observation "mean".
138  * \param Y_predictions_mean [IN] An NxO matrix with the N predictions, each
139  *row containing the mean of one prediction.
140  * \param Y_predictions_cov [IN] An N*OxN*O matrix with the full covariance
141  *matrix of all the N predictions.
142  * \param results [OUT] The output data association hypothesis, and other
143  *useful information.
144  * \param method [IN, optional] The selected method to make the associations.
145  * \param chi2quantile [IN, optional] The threshold for considering a match
146  *between two close Gaussians for two landmarks, in the range [0,1]. It is used
147  *to call mrpt::math::chi2inv
148  * \param use_kd_tree [IN, optional] Build a KD-tree to speed-up the evaluation
149  *of individual compatibility (IC). It's perhaps more efficient to disable it
150  *for a small number of features. (default=true).
151  * \param predictions_IDs [IN, optional] (default:none) An N-vector. If
152  *provided, the resulting associations in "results.associations" will not
153  *contain prediction indices "i", but "predictions_IDs[i]".
154  *
155  * \sa data_association_independent_predictions,
156  *data_association_independent_2d_points,
157  *data_association_independent_3d_points
158  */
160  const mrpt::math::CMatrixDouble& Z_observations_mean,
161  const mrpt::math::CMatrixDouble& Y_predictions_mean,
162  const mrpt::math::CMatrixDouble& Y_predictions_cov,
164  const TDataAssociationMethod method = assocJCBB,
165  const TDataAssociationMetric metric = metricMaha,
166  const double chi2quantile = 0.99, const bool DAT_ASOC_USE_KDTREE = true,
167  const std::vector<prediction_index_t>& predictions_IDs =
168  std::vector<prediction_index_t>(),
169  const TDataAssociationMetric compatibilityTestMetric = metricMaha,
170  const double log_ML_compat_test_threshold = 0.0);
171 
172 /** Computes the data-association between the prediction of a set of landmarks
173  *and their observations, all of them with covariance matrices - Generic
174  *version with NO prediction cross-covariances.
175  * Implemented methods include (see TDataAssociation)
176  * - NN: Nearest-neighbor
177  * - JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]
178  *
179  * With both a Mahalanobis-distance or Matching-likelihood metric. For a
180  *comparison of both methods, see paper:
181  * * J.L. Blanco, J. Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "An
182  *alternative to the Mahalanobis distance for determining optimal
183  *correspondences in data association", IEEE Transactions on Robotics (T-RO),
184  *(2012) DOI: 10.1109/TRO.2012.2193706 Draft:
185  *http://ingmec.ual.es/~jlblanco/papers/blanco2012amd.pdf
186  *
187  * \param Z_observations_mean [IN] An MxO matrix with the M observations, each
188  *row containing the observation "mean".
189  * \param Y_predictions_mean [IN] An NxO matrix with the N predictions, each
190  *row containing the mean of one prediction.
191  * \param Y_predictions_cov [IN] An N*OxO matrix: A vertical stack of N
192  *covariance matrix, one for each of the N prediction.
193  * \param results [OUT] The output data association hypothesis, and other
194  *useful information.
195  * \param method [IN, optional] The selected method to make the associations.
196  * \param chi2quantile [IN, optional] The threshold for considering a match
197  *between two close Gaussians for two landmarks, in the range [0,1]. It is used
198  *to call mrpt::math::chi2inv
199  * \param use_kd_tree [IN, optional] Build a KD-tree to speed-up the evaluation
200  *of individual compatibility (IC). It's perhaps more efficient to disable it
201  *for a small number of features. (default=true).
202  * \param predictions_IDs [IN, optional] (default:none) An N-vector. If
203  *provided, the resulting associations in "results.associations" will not
204  *contain prediction indices "i", but "predictions_IDs[i]".
205  *
206  * \sa data_association_full_covariance,
207  *data_association_independent_2d_points,
208  *data_association_independent_3d_points
209  */
211  const mrpt::math::CMatrixDouble& Z_observations_mean,
212  const mrpt::math::CMatrixDouble& Y_predictions_mean,
213  const mrpt::math::CMatrixDouble& Y_predictions_cov,
215  const TDataAssociationMethod method = assocJCBB,
216  const TDataAssociationMetric metric = metricMaha,
217  const double chi2quantile = 0.99, const bool DAT_ASOC_USE_KDTREE = true,
218  const std::vector<prediction_index_t>& predictions_IDs =
219  std::vector<prediction_index_t>(),
220  const TDataAssociationMetric compatibilityTestMetric = metricMaha,
221  const double log_ML_compat_test_threshold = 0.0);
222 
223 /** @} */
224 
225 /** @} */ // end of grouping
226 
227 }
229 using namespace mrpt::slam;
233 
235 using namespace mrpt::slam;
239 
240 #endif
241 
242 
Nearest-neighbor.
Declares a matrix of booleans (non serializable).
Mahalanobis distance.
size_t prediction_index_t
Used in mrpt::slam::TDataAssociationResults.
mrpt::math::CMatrixDouble indiv_distances
Individual mahalanobis distances (or matching likelihood, depending on the selected metric) between p...
MRPT_FILL_ENUM(assocNN)
JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001].
double distance
The Joint Mahalanobis distance or matching likelihood of the best associations found.
map< string, CVectorDouble > results
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
mrpt::math::CMatrixBool indiv_compatibility
The result of a chi2 test for compatibility using mahalanobis distance - Indices are like in "indiv_d...
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
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.
size_t observation_index_t
Used in mrpt::slam::TDataAssociationResults.
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.
size_t nNodesExploredInJCBB
Only for the JCBB method,the number of recursive calls expent in the algorithm.
The results from mrpt::slam::data_association.
Matching likelihood (See TDataAssociationMetric for a paper explaining this metric) ...
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
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...
std::vector< uint32_t > indiv_compatibility_counts
The sum of each column of indiv_compatibility, that is, the number of compatible pairings for each ob...



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