55 CPosePDFPtr CGridMapAligner::AlignPDF(
64 switch( options.methodSelection )
66 case CGridMapAligner::amCorrelation:
67 return AlignPDF_correlation(mm1,mm2,initialEstimationPDF,runningTime,
info);
69 case CGridMapAligner::amModifiedRANSAC:
70 case CGridMapAligner::amRobustMatch:
72 return AlignPDF_robustMatch(mm1,mm2,initialEstimationPDF,runningTime,
info);
82 bool myVectorOrder(
const pair<size_t,float> & o1,
const pair<size_t,float> & o2 )
84 return o1.second < o2.second;
90 CPosePDFPtr CGridMapAligner::AlignPDF_robustMatch(
99 ASSERT_( options.methodSelection==CGridMapAligner::amRobustMatch || options.methodSelection==CGridMapAligner::amModifiedRANSAC)
112 std::vector<size_t> idxs1,idxs2;
138 else THROW_EXCEPTION(
"Metric maps must be of classes COccupancyGridMap2D or CMultiMetricMap")
144 outInfo.goodness = 1.0f;
146 outInfo.landmarks_map1 = lm1;
147 outInfo.landmarks_map2 = lm2;
159 m_grid_feat_extr.extractFeatures(*m1,*lm1, N1, options.feature_descriptor, options.feature_detector_options );
160 m_grid_feat_extr.extractFeatures(*m2,*lm2, N2, options.feature_descriptor, options.feature_detector_options );
168 const size_t nLM1 = lm1->size();
169 const size_t nLM2 = lm2->size();
173 if (nLM1<2 || nLM2<2)
175 outInfo.goodness = 0;
186 CImage im1(1,1,1),im2(1,1,1);
188 unsigned int corrsCount = 0;
189 std::vector<bool> hasCorr(nLM1,
false);
191 const double thres_max = options.threshold_max;
192 const double thres_delta = options.threshold_delta;
195 if (options.debug_show_corrs)
198 std::cerr <<
"Warning: options.debug_show_corrs has no effect since MRPT 0.9.1\n";
202 for (
size_t idx1=0;idx1<nLM1;idx1++)
205 vector<pair<size_t,float> > corrs_indiv;
206 vector<float> corrs_indiv_only;
207 corrs_indiv.reserve(nLM2);
208 corrs_indiv_only.reserve(nLM2);
210 for (
size_t idx2=0;idx2<nLM2;idx2++)
213 minDist = lm1->landmarks.get(idx1)->features[0]->descriptorDistanceTo( *lm2->landmarks.get(idx2)->features[0]);
215 corrs_indiv.push_back(std::make_pair(idx2,minDist));
216 corrs_indiv_only.push_back(minDist);
226 std::sort(corrs_indiv.begin(),corrs_indiv.end(),
myVectorOrder );
229 const size_t nBestToKeep = corrs_indiv.size();
231 for (
size_t w=0;
w<nBestToKeep;
w++)
233 if (corrs_indiv[
w].second <= thres_max && corrs_indiv[
w].second <= (corr_best+thres_delta) )
235 idxs1.push_back(idx1);
236 idxs2.push_back( corrs_indiv[
w].
first );
242 if (options.debug_show_corrs)
244 auxWin->setWindowTitle(
format(
"Corr: %i - rest",
int(idx1)));
246 auxWin->plot(corrs_indiv_only,
".3",
"the_corr");
249 xs[0]=0; xs[1]=corrs_indiv_only.size()+1;
251 ys[0]=ys[1] = corr_best+thres_delta;
252 auxWin->plot(xs,ys,
"g",
"the_thres");
254 if (idx1==0) auxWin->axis_fit();
255 auxWin->waitForKey();
262 if (options.save_feat_coors)
267 std::map<size_t, std::set<size_t> > corrs_by_idx;
268 for (
size_t l=0;l<idxs1.size();l++)
269 corrs_by_idx[idxs1[l]].insert( idxs2[l] );
271 for (std::map<
size_t, std::set<size_t> >::
iterator it=corrs_by_idx.begin();it!=corrs_by_idx.end();++it)
274 lm1->landmarks.get(it->first)->features[0]->getFirstDescriptorAsMatrix(descriptor1);
276 im1 =
CImage( descriptor1,
true );
278 const size_t FEAT_W = im1.getWidth();
279 const size_t FEAT_H = im1.getHeight();
280 const size_t nF = it->second.size();
282 CImage img_compose( FEAT_W*2 + 15, 10 + (5+FEAT_H) * nF );
289 string fil =
format(
"grid_feats/_FEAT_MATCH_%03i", (
int)it->first );
291 for (j=0,it_j=it->second.begin();j<nF;++j,++it_j)
293 fil+=
format(
"_%u",static_cast<unsigned int>(*it_j) );
296 lm2->landmarks.get( *it_j )->features[0]->getFirstDescriptorAsMatrix(descriptor2);
297 im2 =
CImage( descriptor2,
true );
298 img_compose.
drawImage(10+FEAT_W,5 + j*(FEAT_H+5), im2 );
309 correspondences.clear();
310 for (it1=idxs1.begin(),it2=idxs2.begin();it1!=idxs1.end();++it1,++it2)
314 mp.
this_x = lm1->landmarks.get(*it1)->pose_mean.x;
315 mp.
this_y = lm1->landmarks.get(*it1)->pose_mean.y;
316 mp.
this_z = lm1->landmarks.get(*it1)->pose_mean.z;
319 mp.
other_x = lm2->landmarks.get(*it2)->pose_mean.x;
320 mp.
other_y = lm2->landmarks.get(*it2)->pose_mean.y;
321 mp.
other_z = lm2->landmarks.get(*it2)->pose_mean.z;
322 correspondences.push_back( mp );
331 outInfo.goodness = (2.0f * corrsCount) / (nLM1+nLM2);
339 outInfo.goodness = 0;
341 outInfo.sog1 = pdf_SOG;
342 outInfo.sog2 = pdf_SOG;
343 outInfo.sog3 = pdf_SOG;
349 corrsCount,(
unsigned)correspondences.size(),
350 outInfo.noRobustEstimation.x(),
351 outInfo.noRobustEstimation.y(),
352 RAD2DEG(outInfo.noRobustEstimation.phi() )) );
356 TMapMatchingsToPoseMode sog_modes;
363 if (options.methodSelection== CGridMapAligner::amRobustMatch)
371 const unsigned int min_inliers = options.ransac_minSetSizeRatio *(nLM1+nLM2)/2;
394 size_t nB = pdf_SOG->size();
395 outInfo.sog1 = pdf_SOG;
399 best_mode.
log_w=-std::numeric_limits<double>::max();
401 for (
size_t n=0;
n<pdf_SOG->size();
n++)
410 pdf_SOG->push_back( best_mode );
411 outInfo.sog2 = pdf_SOG;
413 MRPT_LOG_INFO_STREAM(
"[CGridMapAligner] amRobustMatch: "<< nB <<
" SOG modes reduced to "<< pdf_SOG->size() <<
" (most-likely) (min.inliers="<< min_inliers <<
")\n");
423 const size_t nCorrs = all_corrs.size();
432 for (
size_t i=0;i<nLM1;i++) lm1_pnts.
insertPoint( lm1->landmarks.get(i)->pose_mean );
434 for (
size_t i=0;i<nLM2;i++) lm2_pnts.
insertPoint( lm2->landmarks.get(i)->pose_mean );
438 const size_t minInliersTOaccept =
round(options.ransac_minSetSizeRatio * 0.5 * (nLM1+nLM2));
440 const unsigned int ransac_min_nSimulations = 2*(nLM1 + nLM2);
441 unsigned int ransac_nSimulations = 10;
442 const double probability_find_good_model = 0.9999;
449 COV_pnt.get_unsafe(0,0) =
450 COV_pnt.get_unsafe(1,1) =
square( options.ransac_SOG_sigma_m );
459 const unsigned int max_trials = (nCorrs*(nCorrs-1)/2) * 5 ;
461 unsigned int iter = 0;
462 unsigned int trials = 0;
463 while (iter<ransac_nSimulations && trials<max_trials )
478 if (all_corrs[ idx1 ].this_idx==all_corrs[ idx2 ].this_idx ||
479 all_corrs[ idx1 ].this_idx==all_corrs[ idx2 ].other_idx )
continue;
480 if (all_corrs[ idx1 ].other_idx==all_corrs[ idx2 ].this_idx ||
481 all_corrs[ idx1 ].other_idx==all_corrs[ idx2 ].other_idx )
continue;
487 all_corrs[ idx1 ].this_x, all_corrs[ idx1 ].this_y, all_corrs[ idx1 ].this_z,
488 all_corrs[ idx2 ].this_x, all_corrs[ idx2 ].this_y, all_corrs[ idx2 ].this_z );
491 all_corrs[ idx1 ].other_x, all_corrs[ idx1 ].other_y, all_corrs[ idx1 ].other_z,
492 all_corrs[ idx2 ].other_x, all_corrs[ idx2 ].other_y, all_corrs[ idx2 ].other_z );
497 const double corrs_dist_chi2 =
499 (8.0*
square(options.ransac_SOG_sigma_m) * (
square(corrs_dist1)+
square(corrs_dist2)) );
501 if (corrs_dist_chi2 > chi2_thres_dim1 )
507 bool is_new_hyp =
true;
510 if (itOldHyps->first.contains( all_corrs[ idx1 ] ) &&
511 itOldHyps->first.contains( all_corrs[ idx2 ] ) )
514 itOldHyps->second.log_w = std::log( std::exp(itOldHyps->second.log_w) + 1.0 );
523 tentativeSubSet.push_back( all_corrs[ idx1 ] );
524 tentativeSubSet.push_back( all_corrs[ idx2 ] );
530 used_landmarks1[ all_corrs[ idx1 ].this_idx ] =
true;
531 used_landmarks1[ all_corrs[ idx2 ].this_idx ] =
true;
532 used_landmarks2[ all_corrs[ idx1 ].other_idx] =
true;
533 used_landmarks2[ all_corrs[ idx2 ].other_idx] =
true;
537 bool keep_incorporating =
true;
545 temptPose.
cov *=
square( options.ransac_SOG_sigma_m );
552 const double ccos = cos(temptPose.
mean.
phi());
553 const double ssin = sin(temptPose.
mean.
phi());
556 Hc.get_unsafe(1,1) = ccos;
557 Hc.get_unsafe(0,0) = ccos;
558 Hc.get_unsafe(1,0) = ssin;
559 Hc.get_unsafe(0,1) = -ssin;
566 vector<float> matches_dist;
567 std::vector<size_t> matches_idx;
574 #define GRIDMAP_USE_PROD_INTEGRAL 576 #ifdef GRIDMAP_USE_PROD_INTEGRAL 577 double best_pair_value = 0;
579 double best_pair_value = std::numeric_limits<double>::max();
581 double best_pair_d2 = std::numeric_limits<double>::max();
582 pair<size_t,size_t> best_pair_ij;
587 CDisplayWindowPlots win(
"Matches");
589 for (
size_t j=0;j<nLM2;j++)
591 if ( used_landmarks2[j] )
continue;
595 pdf_M2_j.
cov.get_unsafe(0,0) =
596 pdf_M2_j.
cov.get_unsafe(1,1) =
square( options.ransac_SOG_sigma_m );
599 win.plotEllipse( pdf_M2_j.
mean.
x(),pdf_M2_j.
mean.
y(),pdf_M2_j.
cov,2,
"b-",
format(
"M2_%u",(
unsigned)j),
true);
602 static const unsigned int N_KDTREE_SEARCHED = 3;
612 for (
size_t u=0;u<matches_idx.size();u++)
614 if ( used_landmarks1[ matches_idx[u] ] )
continue;
617 Hq.get_unsafe(0,2) = -p2_j_local.
x*ssin - p2_j_local.
y*ccos;
618 Hq.get_unsafe(1,2) = p2_j_local.
x*ccos - p2_j_local.
y*ssin;
621 Hc.multiply_HCHt(COV_pnt,pdf_M1_i.
cov);
622 Hq.multiply_HCHt(temptPose.
cov,pdf_M1_i.
cov,
true);
625 lm1_pnts.
getPoint(matches_idx[u], px,py);
630 win.plotEllipse( pdf_M1_i.
mean.
x(),pdf_M1_i.
mean.
y(),pdf_M1_i.
cov,2,
"r-",
format(
"M1_%u",(
unsigned)matches_idx[u]),
true);
635 #ifdef GRIDMAP_USE_PROD_INTEGRAL 639 if (prod_ij>best_pair_value)
642 if (prod_ij<best_pair_value)
647 best_pair_value = prod_ij;
648 best_pair_ij.first = matches_idx[u];
649 best_pair_ij.second = j;
668 keep_incorporating =
false;
671 if (best_pair_d2 < chi2_thres_dim2 )
678 float p1_i_localx, p1_i_localy;
679 float p2_j_localx, p2_j_localy;
680 lm1_pnts.
getPoint(best_pair_ij.first, p1_i_localx, p1_i_localy);
681 lm2_pnts.
getPoint(best_pair_ij.second,p2_j_localx, p2_j_localy);
683 used_landmarks1[ best_pair_ij.first ] =
true;
684 used_landmarks2[ best_pair_ij.second ] =
true;
689 p1_i_localx, p1_i_localy,0,
690 p2_j_localx, p2_j_localy,0
693 keep_incorporating =
true;
697 }
while (keep_incorporating);
700 const size_t ninliers = tentativeSubSet.size();
701 if (ninliers > minInliersTOaccept)
706 newGauss.
cov = temptPose.
cov;
708 sog_modes[ tentativeSubSet ] = newGauss;
714 if (largestConsensusCorrs.size()<ninliers )
716 largestConsensusCorrs = tentativeSubSet;
720 const double fracinliers = ninliers/
static_cast<double>(
std::min(nLM1,nLM2));
721 double pNoOutliers = 1 - pow(fracinliers,static_cast<double>(2.0 ));
723 pNoOutliers = std::max( std::numeric_limits<double>::epsilon(), pNoOutliers);
724 pNoOutliers =
std::min(1.0 - std::numeric_limits<double>::epsilon() , pNoOutliers);
726 ransac_nSimulations = log(1-probability_find_good_model)/log(pNoOutliers);
728 if (ransac_nSimulations<ransac_min_nSimulations)
729 ransac_nSimulations = ransac_min_nSimulations;
742 cout <<
"SOG mode: " <<
s->second.mean <<
" inliers: " <<
s->first.size() << endl;
743 pdf_SOG->push_back(
s->second);
747 if (pdf_SOG->size()>0)
748 pdf_SOG->normalizeWeights();
752 size_t nB = pdf_SOG->size();
753 outInfo.sog1 = pdf_SOG;
756 pdf_SOG->mergeModes( options.maxKLd_for_merge,
false);
757 const double merge_clock_tim = merge_clock.
Tac();
759 outInfo.sog2 = pdf_SOG;
760 size_t nA = pdf_SOG->size();
761 MRPT_LOG_INFO(
mrpt::format(
"[CGridMapAligner] amModifiedRANSAC: %u SOG modes merged to %u in %.03fsec\n", (
unsigned int)nB, (
unsigned int)nA, merge_clock_tim ) );
767 if (options.debug_save_map_pairs)
769 static unsigned int NN = 0;
774 printf(
" Largest consensus: %u\n", static_cast<unsigned>(largestConsensusCorrs.size()) );
776 CEnhancedMetaFile::LINUX_IMG_HEIGHT = max(m1->
getSizeY(), m2->
getSizeY()) + 50;
780 COccupancyGridMap2D::saveAsEMFTwoMapsWithCorrespondences(
781 format(
"__debug_corrsGrid_%05u.emf",NN),
783 COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
784 format(
"__debug_corrsGrid_%05u.png",NN),
798 if (multimap1 && multimap2 &&
816 outInfo.icp_goodness_all_sog_modes.clear();
819 CPosePDFPtr icp_est = icp.
Align(pnts1.pointer(),pnts2.pointer(),(i)->
mean,NULL,&icpInfo);
830 cout <<
"ICP " << cnt <<
" log-w: " << i->log_w <<
" Goodness: " << 100*icpInfo.
goodness <<
" D_M= " << icp_maha_dist << endl;
831 cout <<
" final pos: " << icp_est->getMeanVal() << endl;
832 cout <<
" org pos: " << i->mean << endl;
834 outInfo.icp_goodness_all_sog_modes.push_back(icpInfo.
goodness);
837 if (icpInfo.
goodness > options.min_ICP_goodness &&
838 icp_maha_dist < options.max_ICP_mahadist
841 icp_est->getMean((i)->
mean);
846 i = pdf_SOG->erase(i);
852 outInfo.sog3 = pdf_SOG;
854 pdf_SOG->mergeModes( options.maxKLd_for_merge,
false );
866 MRPT_TODO(
"Refactor `info` so it is polymorphic and can use dynamic_cast<> here");
875 *runningTime = tictac->
Tac();
887 CPosePDFPtr CGridMapAligner::AlignPDF_correlation(
923 float phiResolution =
DEG2RAD( 0.2f );
924 float phiMin = -
M_PIf+0.5f*phiResolution;
925 float phiMax =
M_PIf;
930 float pivotPt_x = 0.5f*(m1->getXMax()+m1->getXMin());
931 float pivotPt_y = 0.5f*(m1->getYMax()+m1->getYMin());
934 float currentMaxCorr = -1e6f;
936 m1->getAsImage(map1_img);
938 map2_mod.
setSize( m1->getXMin(),m1->getXMax(),m1->getYMin(),m1->getYMax(),m1->getResolution() );
939 size_t map2_lx = map2_mod.
getSizeX();
940 size_t map2_ly = map2_mod.
getSizeY();
941 CMatrix outCrossCorr,bestCrossCorr;
944 #ifdef CORRELATION_SHOW_DEBUG 945 CDisplayWindow *win =
new CDisplayWindow(
"corr");
946 CDisplayWindow *win2 =
new CDisplayWindow(
"map2_mod");
952 for (phi=phiMin;phi<phiMax;phi+=phiResolution)
957 pivotPt_x - cos(phi)*map2width_2,
958 pivotPt_y - sin(phi)*map2width_2,
963 for (
unsigned int cy2=0;cy2<map2_ly;cy2++)
966 for (
unsigned int cx2=0;cx2<map2_lx;cx2++)
985 float corrPeak = outCrossCorr.maxCoeff();
986 printf(
"phi = %fdeg \tmax corr=%f\n",
RAD2DEG(phi), corrPeak );
989 if (corrPeak>currentMaxCorr)
991 currentMaxCorr = corrPeak;
992 bestCrossCorr = outCrossCorr;
996 #ifdef CORRELATION_SHOW_DEBUG 997 outCrossCorr.adjustRange(0,1);
998 CImage aux( outCrossCorr,
true );
1000 win2->showImage(map2_img);
1008 *runningTime = tictac->Tac();
1012 bestCrossCorr.normalize(0,1);
1013 CImage aux( bestCrossCorr,
true );
1016 #ifdef CORRELATION_SHOW_DEBUG 1022 CMatrix::Index uMax,vMax;
1023 currentMaxCorr = bestCrossCorr.maxCoeff(&uMax,&vMax);
1025 PDF->mean.x( m1->idx2x( uMax ) );
1026 PDF->mean.y( m1->idx2y( vMax ) );
1038 CGridMapAligner::TConfigParams::TConfigParams() :
1042 feature_detector_options(),
1044 ransac_minSetSizeRatio ( 0.20f ),
1045 ransac_SOG_sigma_m ( 0.10f ),
1047 ransac_chi2_quantile ( 0.99 ),
1048 ransac_prob_good_inliers( 0.9999 ),
1049 featsPerSquareMeter ( 0.015f ),
1050 threshold_max ( 0.15f ),
1051 threshold_delta ( 0.10f ),
1052 min_ICP_goodness ( 0.30f ),
1053 max_ICP_mahadist ( 10.0 ),
1054 maxKLd_for_merge ( 0.9 ),
1056 save_feat_coors ( false ),
1057 debug_show_corrs ( false ),
1058 debug_save_map_pairs ( false )
1067 out.
printf(
"\n----------- [CGridMapAligner::TConfigParams] ------------ \n\n");
1087 feature_detector_options.dumpToTextStream(out);
1121 feature_detector_options.loadFromConfigFile(iniFile,section);
A namespace of pseudo-random numbers genrators of diferent distributions.
uint32_t drawUniform32bit()
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, in the whole range of 32-bit integers.
float getXMax() const
Returns the "x" coordinate of right side of grid map.
CPoint2D mean
The mean value.
double x() const
Common members of all points & poses classes.
static CPosePDFGaussianPtr Create()
double getArea() const
Returns the area of the gridmap, in square meters.
bool BASE_IMPEXP createDirectory(const std::string &dirName)
Creates a directory.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
double productIntegralWith(const CPoint2DPDFGaussian &p) const
Computes the "correspondence likelihood" of this PDF with another one: This is implemented as the int...
CPose2D mean
The mean value.
static CPosePDFSOGPtr Create()
mrpt::poses::CPosePDFPtr Align(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, float *runningTime=NULL, void *info=NULL)
The method for aligning a pair of metric maps, aligning only 2D + orientation.
The struct for each mode:
float getResolution() const
Returns the resolution of the grid map.
double distanceTo(const CPoseOrPoint< OTHERCLASS > &b) const
Returns the Euclidean distance to another pose/point:
A gaussian distribution for 2D points.
A class for aligning two multi-metric maps (with an occupancy grid maps and a points map...
A class for storing images as grayscale or RGB bitmaps.
TAlignerMethod
The type for selecting the grid-map alignment algorithm.
Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a ...
Parameters for se2_l2_robust().
#define MRPT_LOAD_CONFIG_VAR_NO_DEFAULT(variableName, variableType, configFileObject, sectionNameStr)
#define THROW_EXCEPTION(msg)
mrpt::utils::TMatchingPairList largestSubSet
the largest consensus sub-set
BASE_IMPEXP CRandomGenerator randomGenerator
A static instance of a CRandomGenerator class, for use in single-thread applications.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
This file implements several operations that operate element-wise on individual or pairs of container...
bool ransac_fuseByCorrsMatch
(Default = true) If true, the weight of Gaussian modes will be increased when an exact match in the s...
unsigned int ransac_nSimulations
(Default = 0) If set to 0, an adaptive algorithm is used to determine the number of iterations...
unsigned int ransac_minSetSize
(Default=3)
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
const float ransac_mahalanobisDistanceThreshold
bool myVectorOrder(const pair< size_t, float > &o1, const pair< size_t, float > &o2)
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void insertPoint(float x, float y, float z=0)
Provides a way to insert (append) individual points into the map: the missing fields of child classes...
bool TFEST_IMPEXP se2_l2_robust(const mrpt::utils::TMatchingPairList &in_correspondences, const double in_normalizationStd, const TSE2RobustParams &in_ransac_params, TSE2RobustResult &out_results)
Robust least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference ...
const Scalar * const_iterator
double mahalanobisDistanceTo(const CPosePDFGaussian &theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
void kdTreeNClosestPoint2DIdx(float x0, float y0, size_t knn, std::vector< size_t > &out_idx, std::vector< float > &out_dist_sqr) const
KD Tree-based search for the N closest point to some given 2D coordinates and returns their indexes...
The ICP algorithm return information.
ProxyFilterContainerByClass< mrpt::maps::COccupancyGridMap2DPtr, TListMaps > m_gridMaps
STL-like proxy to access this kind of maps in maps.
TConfigParams options
The options employed by the ICP align.
void Tic()
Starts the stopwatch.
mrpt::math::CMatrixDouble33 cov
The 3x3 covariance matrix.
void getAsImage(utils::CImage &img, bool verticalFlip=false, bool forceRGB=false, bool tricolor=false) const
Returns the grid as a 8-bit graylevel image, where each pixel is a cell (output image is RGB only if ...
mrpt::poses::CPose3DPDFPtr Align3DPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=NULL, void *info=NULL)
Not applicable in this class, will launch an exception.
GLubyte GLubyte GLubyte GLubyte w
This class allows loading and storing values and vectors of different types from a configuration text...
T square(const T x)
Inline function for the square of a number.
std::vector< bool > vector_bool
A type for passing a vector of bools.
bool verbose
(Default=false)
void cross_correlation_FFT(const CImage &in_img, math::CMatrixFloat &out_corr, int u_search_ini=-1, int v_search_ini=-1, int u_search_size=-1, int v_search_size=-1, float biasThisImg=0, float biasInImg=0) const
Computes the correlation matrix between this image and another one.
CONTAINER::Scalar minimum(const CONTAINER &v)
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
unsigned int ransac_maxSetSize
(Default = 20)
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
float getXMin() const
Returns the "x" coordinate of left side of grid map.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
mrpt::maps::CLandmarksMapPtr CLandmarksMapPtr
Backward compatible typedef.
void BASE_IMPEXP sleep(int time_ms) MRPT_NO_THROWS
An OS-independent method for sending the current thread to "sleep" for a given period of time...
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
#define MRPT_LOG_INFO(_STRING)
#define MRPT_LOAD_CONFIG_VAR_CAST(variableName, variableType, variableTypeCast, configFileObject, sectionNameStr)
unsigned int maxIterations
Maximum number of iterations to run.
This class implements a high-performance stopwatch.
bool ransac_algorithmForLandmarks
(Default = true) Use Mahalanobis distance (true) or Euclidean dist (false)
mrpt::math::CMatrixDouble33 cov
GLfloat GLfloat GLfloat GLfloat v3
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
unsigned int getSizeX() const
Returns the horizontal size of grid map in cells count.
Classes for computer vision, detectors, features, etc.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
mrpt::maps::CLandmarksMap CLandmarksMap
Backward compatible typedef.
GLsizei const GLchar ** string
double ransac_mahalanobisDistanceThreshold
(Default = 3.0)
A class used to store a 2D point.
double ransac_fuseMaxDiffPhi
(Default=0.1degree) (In radians)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
TDescriptorType
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescri...
virtual void filledRectangle(int x0, int y0, int x1, int y1, const mrpt::utils::TColor color)
Draws a filled rectangle.
#define CLASS_ID(class_name)
Access to runtime class ID for a defined class name.
A class for storing an occupancy grid map.
unsigned long getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
#define MRPT_LOAD_CONFIG_VAR(variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
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...
static cellType p2l(const float p)
Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the val...
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
cellType * getRow(int cy)
Access to a "row": mainly used for drawing grid as a bitmap efficiently, do not use it normally...
float smallestThresholdDist
The size for threshold such that iterations will stop, since it is considered precise enough...
const double & phi() const
Get the phi angle of the 2D pose (in radians)
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::utils::CSerializable) is of t...
GLenum GLenum GLvoid * row
The ICP algorithm return information.
double mean(const CONTAINER &v)
Computes the mean value of a vector.
double Tac()
Stops the stopwatch.
float idx2y(const size_t cy) const
A matrix of dynamic size.
mrpt::poses::CPosePDFSOG transformation
The output as a set of transformations (sum of Gaussians)
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
int round(const T value)
Returns the closer integer (int) to x.
bool saveToFile(const std::string &fileName, int jpeg_quality=95) const
Save the image to a file, whose format is determined from the extension (internally uses OpenCV)...
bool BASE_IMPEXP deleteFilesInDirectory(const std::string &s, bool deleteDirectoryAsWell=false)
Delete all the files in a given directory (nothing done if directory does not exists, or path is a file).
#define MRPT_LOAD_CONFIG_VAR_CAST_NO_DEFAULT(variableName, variableType, variableTypeCast, configFileObject, sectionNameStr)
float getPos(float x, float y) const
Read the real valued [0,1] contents of a cell, given its coordinates.
T distanceBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the distance between 2 points in 2D.
GLfloat GLfloat GLfloat v2
CListGaussianModes::iterator iterator
void setSize(float x_min, float x_max, float y_min, float y_max, float resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
virtual void reserve(size_t newLength) MRPT_OVERRIDE
Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
ProxyFilterContainerByClass< mrpt::maps::CSimplePointsMapPtr, TListMaps > m_pointsMaps
STL-like proxy to access this kind of maps in maps.
This class stores any customizable set of metric maps.
unsigned int getSizeY() const
Returns the vertical size of grid map in cells count.
This class is a "CSerializable" wrapper for "CMatrixFloat".
bool TFEST_IMPEXP se2_l2(const mrpt::utils::TMatchingPairList &in_correspondences, mrpt::math::TPose2D &out_transformation, mrpt::math::CMatrixDouble33 *out_estimateCovariance=NULL)
Least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference frames...
unsigned __int32 uint32_t
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const
Returns information about the class of an object in runtime.
double log_w
The log-weight.
mrpt::math::CMatrixDouble22 cov
The 2x2 covariance matrix.
int16_t cellType
The type of the map cells:
size_t getWidth() const MRPT_OVERRIDE
Returns the width of the image in pixels.
Output placeholder for se2_l2_robust()
virtual void drawImage(int x, int y, const utils::CImage &img)
Draws an image as a bitmap at a given position.
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
double ransac_fuseMaxDiffXY
(Default = 0.01)
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
size_t getHeight() const MRPT_OVERRIDE
Returns the height of the image in pixels.
double probability_find_good_model
(Default = 0.999) See parameter ransac_nSimulations. When using probability_find_good_model, the minimum number of iterations can be set with ransac_min_nSimulations
double mahalanobisDistanceTo(const CPoint2DPDFGaussian &other) const
Returns the Mahalanobis distance from this PDF to another PDF, that is, it's evaluation at (0...
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.