34 #include <mrpt/otherlibs/nanoflann/nanoflann.hpp> 62 template <
typename T, TDataAssociationMetric METRIC>
72 const size_t N =
info.currentAssociation.size();
82 indices_obs[i] = it->first;
83 indices_pred[i] = it->second;
92 Eigen::Matrix<T,Eigen::Dynamic,Eigen::Dynamic> COV;
93 Y_predictions_cov.extractSubmatrixSymmetricalBlocks(
102 Eigen::Matrix<T,Eigen::Dynamic,1> innovations(N *
info.length_O);
103 T *dst_ptr= &innovations[0];
106 const T *pred_i_mean = Y_predictions_mean.get_unsafe_row( it->second );
107 const T *obs_i_mean = Z_observations_mean.get_unsafe_row( it->first );
109 for (
unsigned int k=0;k<
info.length_O;k++)
110 *dst_ptr++ = pred_i_mean[k]-obs_i_mean[k];
115 COV.inv_fast(COV_inv);
125 const T cov_det = COV.det();
126 const double ml = exp(-0.5*d2) / ( std::pow(
M_2PI,
info.length_O * 0.5) * std::sqrt(cov_det) );
130 template<TDataAssociationMetric METRIC>
147 template <
typename T, TDataAssociationMetric METRIC>
158 if (curObsIdx>=
info.nObservations)
164 results.
distance = joint_pdf_metric<T,METRIC>(
166 Y_predictions_mean, Y_predictions_cov,
170 else if ( !
info.currentAssociation.empty() &&
info.currentAssociation.size()==results.
associations.size() )
173 const double d2 = joint_pdf_metric<T,METRIC>(
175 Y_predictions_mean, Y_predictions_cov,
179 if (isCloser<METRIC>(d2,results.
distance))
200 if ((
info.currentAssociation.size() + potentials) >= results.
associations.size())
206 bool already_asigned =
false;
209 if (itS->second==predIdx)
211 already_asigned =
true;
216 if (!already_asigned)
224 JCBB_recursive<T,METRIC>(
225 Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
226 results, new_info, curObsIdx+1);
233 if ((
info.currentAssociation.size() + potentials) >= results.
associations.size() )
239 JCBB_recursive<T,METRIC>(
240 Z_observations_mean, Y_predictions_mean, Y_predictions_cov,
241 results,
info, curObsIdx+1);
280 const double chi2quantile,
281 const bool DAT_ASOC_USE_KDTREE,
282 const std::vector<prediction_index_t> &predictions_IDs,
284 const double log_ML_compat_test_threshold
289 using nanoflann::KDTreeEigenMatrixAdaptor;
295 const size_t nPredictions =
size(Y_predictions_mean,1);
296 const size_t nObservations =
size(Z_observations_mean,1);
298 const size_t length_O =
size(Z_observations_mean,2);
303 ASSERT_( length_O*nPredictions ==
size(Y_predictions_cov,1))
304 ASSERT_( Y_predictions_cov.isSquare() )
306 ASSERT_( chi2quantile>0 && chi2quantile<1 )
315 typedef std::unique_ptr<KDTreeEigenMatrixAdaptor<CMatrixDouble> > KDTreeMatrixPtr;
317 typedef std::auto_ptr<KDTreeEigenMatrixAdaptor<CMatrixDouble> > KDTreeMatrixPtr;
319 KDTreeMatrixPtr kd_tree;
320 const size_t N_KD_RESULTS = nPredictions;
321 std::vector<double> kd_result_distances(DAT_ASOC_USE_KDTREE ? N_KD_RESULTS : 0);
322 std::vector<CMatrixDouble::Index> kd_result_indices(DAT_ASOC_USE_KDTREE ? N_KD_RESULTS : 0);
323 std::vector<double> kd_queryPoint(DAT_ASOC_USE_KDTREE ? length_O : 0);
325 if (DAT_ASOC_USE_KDTREE)
328 kd_tree = KDTreeMatrixPtr(
new KDTreeEigenMatrixAdaptor<CMatrixDouble>(length_O, Y_predictions_mean) );
332 results.
distance = (metric==
metricML) ? 0 : std::numeric_limits<double>::max();
349 Eigen::VectorXd diff_means_i_j(length_O);
351 for (
size_t j=0;j<nObservations;++j)
353 if (!DAT_ASOC_USE_KDTREE)
356 for (
size_t i=0;i<nPredictions;++i)
359 const size_t pred_cov_idx = i*length_O;
360 Y_predictions_cov.extractMatrix(pred_cov_idx,pred_cov_idx,length_O,length_O, pred_i_cov);
362 for (
size_t k=0;k<length_O;k++)
363 diff_means_i_j[k] = Z_observations_mean.get_unsafe(j,k) - Y_predictions_mean.get_unsafe(i,k);
375 const bool IC = (compatibilityTestMetric==
metricML) ? (ml > log_ML_compat_test_threshold) : (d2 < chi2thres);
384 for (
size_t k=0;k<length_O;k++)
385 kd_queryPoint[k] = Z_observations_mean.get_unsafe(j,k);
387 kd_tree->query(&kd_queryPoint[0], N_KD_RESULTS, &kd_result_indices[0], &kd_result_distances[0] );
390 for (
size_t w=0;
w<N_KD_RESULTS;
w++)
392 const size_t i = kd_result_indices[
w];
395 const size_t pred_cov_idx = i*length_O;
396 Y_predictions_cov.extractMatrix(pred_cov_idx,pred_cov_idx,length_O,length_O, pred_i_cov);
398 for (
size_t k=0;k<length_O;k++)
399 diff_means_i_j[k] = Z_observations_mean.get_unsafe(j,k) - Y_predictions_mean.get_unsafe(i,k);
405 if (d2>6*chi2thres)
break;
413 const bool IC = (compatibilityTestMetric==
metricML) ? (ml > log_ML_compat_test_threshold) : (d2 < chi2thres);
441 typedef multimap<double, pair<observation_index_t, multimap<double,prediction_index_t> > > TListAllICs;
442 TListAllICs lst_all_ICs;
446 multimap<double,prediction_index_t> ICs;
454 ICs.insert(make_pair(d2,i));
460 const double best_dist = ICs.begin()->first;
461 lst_all_ICs.insert(make_pair( best_dist, make_pair(j,ICs) ) );
468 std::set<prediction_index_t> lst_already_taken_preds;
473 const multimap<double,prediction_index_t> &lstCompats = it->second.second;
477 if (lst_already_taken_preds.find(itP->second) ==lst_already_taken_preds.end() )
481 lst_already_taken_preds.insert(itP->second);
496 info.nPredictions = nPredictions;
497 info.nObservations = nObservations;
498 info.length_O = length_O;
501 JCBB_recursive<CMatrixDouble::Scalar,metricMaha>(Z_observations_mean, Y_predictions_mean, Y_predictions_cov,results,
info, 0 );
503 JCBB_recursive<CMatrixDouble::Scalar,metricML>(Z_observations_mean, Y_predictions_mean, Y_predictions_cov,results,
info, 0 );
513 if (!predictions_IDs.empty())
515 ASSERT_( predictions_IDs.size()==nPredictions );
517 itAssoc->second = predictions_IDs[itAssoc->second];
535 const double chi2quantile,
536 const bool DAT_ASOC_USE_KDTREE,
537 const std::vector<prediction_index_t> &predictions_IDs,
539 const double log_ML_compat_test_threshold
546 const size_t nPredictions =
size(Y_predictions_mean,1);
547 const size_t nObservations =
size(Z_observations_mean,1);
549 const size_t length_O =
size(Z_observations_mean,2);
554 ASSERT_( length_O*nPredictions ==
size(Y_predictions_cov_stacked,1))
556 ASSERT_( chi2quantile>0 && chi2quantile<1 )
562 CMatrixDouble Y_predictions_cov_full(length_O*nPredictions,length_O*nPredictions);
564 for (
size_t i=0;i<nPredictions;i++)
566 const size_t idx = i*length_O;
567 Y_predictions_cov_stacked.extractSubmatrix(idx,idx+length_O-1,0,length_O-1, COV_i);
568 Y_predictions_cov_full.insertMatrix(idx,idx,COV_i);
573 Y_predictions_mean,Y_predictions_cov_full,
574 results, method, metric, chi2quantile,
575 DAT_ASOC_USE_KDTREE, predictions_IDs,
576 compatibilityTestMetric, log_ML_compat_test_threshold );
bool isCloser< metricML >(const double v1, const double v2)
const T & get_unsafe(size_t row, size_t col) const
Fast but unsafe method to read a value from the matrix.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
size_t observation_index_t
Used in mrpt::slam::TDataAssociationResults.
vector_uint indiv_compatibility_counts
The sum of each column of indiv_compatibility, that is, the number of compatible pairings for each ob...
#define THROW_EXCEPTION(msg)
mrpt::math::CMatrixDouble indiv_distances
Individual mahalanobis distances (or matching likelihood, depending on the selected metric) between p...
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)
const Scalar * const_iterator
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
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...
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.
double distance
The Joint Mahalanobis distance or matching likelihood of the best associations found.
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...
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
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...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void SLAM_IMPEXP 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...
std::map< size_t, size_t > currentAssociation
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double BASE_IMPEXP chi2inv(double P, unsigned int dim=1)
The "quantile" of the Chi-Square distribution, for dimension "dim" and probability 0<P<1 (the inverse...
A matrix of dynamic size.
size_t getRowCount() const
Number of rows in the matrix.
size_t prediction_index_t
Used in mrpt::slam::TDataAssociationResults.
std::vector< size_t > vector_size_t
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.
GLfloat GLfloat GLfloat v2
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.
bool isCloser(const double v1, const double v2)
void SLAM_IMPEXP 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...
void fillAll(const T &val)