MRPT
1.9.9
|
Classes | |
struct | mrpt::slam::TDataAssociationResults |
The results from mrpt::slam::data_association. More... | |
Data association | |
enum | mrpt::slam::TDataAssociationMethod { mrpt::slam::assocNN = 0, mrpt::slam::assocJCBB } |
Different algorithms for data association, used in mrpt::slam::data_association. More... | |
enum | mrpt::slam::TDataAssociationMetric { mrpt::slam::metricMaha = 0, mrpt::slam::metricML } |
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both methods see paper: More... | |
using | mrpt::slam::observation_index_t = size_t |
Used in mrpt::slam::TDataAssociationResults. More... | |
using | mrpt::slam::prediction_index_t = size_t |
Used in mrpt::slam::TDataAssociationResults. More... | |
void | mrpt::slam::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, all of them with covariance matrices - Generic version with prediction full cross-covariances. More... | |
void | mrpt::slam::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, all of them with covariance matrices - Generic version with NO prediction cross-covariances. More... | |
using mrpt::slam::observation_index_t = typedef size_t |
Used in mrpt::slam::TDataAssociationResults.
Definition at line 55 of file data_association.h.
using mrpt::slam::prediction_index_t = typedef size_t |
Used in mrpt::slam::TDataAssociationResults.
Definition at line 57 of file data_association.h.
Different algorithms for data association, used in mrpt::slam::data_association.
Enumerator | |
---|---|
assocNN | Nearest-neighbor. |
assocJCBB | JCBB: Joint Compatibility Branch & Bound [Neira, Tardos 2001]. |
Definition at line 29 of file data_association.h.
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both methods see paper:
Enumerator | |
---|---|
metricMaha | Mahalanobis distance. |
metricML | Matching likelihood (See TDataAssociationMetric for a paper explaining this metric) |
Definition at line 45 of file data_association.h.
void mrpt::slam::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, all of them with covariance matrices - Generic version with prediction full cross-covariances.
Implemented methods include (see TDataAssociation)
With both a Mahalanobis-distance or Matching-likelihood metric. For a comparison of both methods, see paper:
Z_observations_mean | [IN] An MxO matrix with the M observations, each row containing the observation "mean". |
Y_predictions_mean | [IN] An NxO matrix with the N predictions, each row containing the mean of one prediction. |
Y_predictions_cov | [IN] An N*OxN*O matrix with the full covariance matrix of all the N predictions. |
results | [OUT] The output data association hypothesis, and other useful information. |
method | [IN, optional] The selected method to make the associations. |
chi2quantile | [IN, optional] The threshold for considering a match between two close Gaussians for two landmarks, in the range [0,1]. It is used to call mrpt::math::chi2inv |
use_kd_tree | [IN, optional] Build a KD-tree to speed-up the evaluation of individual compatibility (IC). It's perhaps more efficient to disable it for a small number of features. (default=true). |
predictions_IDs | [IN, optional] (default:none) An N-vector. If provided, the resulting associations in "results.associations" will not contain prediction indices "i", but "predictions_IDs[i]". |
Definition at line 297 of file data_association.cpp.
References mrpt::math::CMatrixDynamic< T >::asEigen(), ASSERT_, mrpt::slam::assocJCBB, mrpt::slam::assocNN, mrpt::math::chi2inv(), mrpt::math::CMatrixDynamic< T >::cols(), mrpt::math::MatrixVectorBase< Scalar, Derived >::isSquare(), mrpt::slam::TAuxDataRecursiveJCBB::length_O, mrpt::math::mahalanobisDistance2AndLogPDF(), mrpt::slam::metricMaha, mrpt::slam::metricML, MRPT_END, MRPT_START, mrpt::slam::TAuxDataRecursiveJCBB::nObservations, mrpt::slam::TAuxDataRecursiveJCBB::nPredictions, results, mrpt::math::CMatrixDynamic< T >::rows(), THROW_EXCEPTION, and val.
Referenced by mrpt::slam::data_association_independent_predictions(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationsAndDataAssociation(), and mrpt::slam::CRangeBearingKFSLAM::OnGetObservationsAndDataAssociation().
void mrpt::slam::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, all of them with covariance matrices - Generic version with NO prediction cross-covariances.
Implemented methods include (see TDataAssociation)
With both a Mahalanobis-distance or Matching-likelihood metric. For a comparison of both methods, see paper:
Z_observations_mean | [IN] An MxO matrix with the M observations, each row containing the observation "mean". |
Y_predictions_mean | [IN] An NxO matrix with the N predictions, each row containing the mean of one prediction. |
Y_predictions_cov | [IN] An N*OxO matrix: A vertical stack of N covariance matrix, one for each of the N prediction. |
results | [OUT] The output data association hypothesis, and other useful information. |
method | [IN, optional] The selected method to make the associations. |
chi2quantile | [IN, optional] The threshold for considering a match between two close Gaussians for two landmarks, in the range [0,1]. It is used to call mrpt::math::chi2inv |
use_kd_tree | [IN, optional] Build a KD-tree to speed-up the evaluation of individual compatibility (IC). It's perhaps more efficient to disable it for a small number of features. (default=true). |
predictions_IDs | [IN, optional] (default:none) An N-vector. If provided, the resulting associations in "results.associations" will not contain prediction indices "i", but "predictions_IDs[i]". |
Definition at line 575 of file data_association.cpp.
References ASSERT_, mrpt::math::CMatrixDynamic< T >::cols(), mrpt::slam::data_association_full_covariance(), mrpt::math::MatrixBase< Scalar, Derived >::extractMatrix(), mrpt::math::MatrixBase< Scalar, Derived >::insertMatrix(), mrpt::slam::metricMaha, mrpt::slam::metricML, MRPT_END, MRPT_START, results, and mrpt::math::CMatrixDynamic< T >::rows().
Referenced by TEST().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020 |