9 #ifndef data_association_H    10 #define data_association_H   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>(),
   170     const double log_ML_compat_test_threshold = 0.0);
   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>(),
   221     const double log_ML_compat_test_threshold = 0.0);
   235 using namespace 
mrpt::slam;
 
Declares a matrix of booleans (non serializable). 
 
TDataAssociationResults()
 
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...
 
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()
 
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)
 
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...