Skip to content

Commit

Permalink
GridMapAligner: code clean up and add bibliographic reference
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Apr 23, 2024
1 parent b2c014f commit 0e53b10
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 24 deletions.
11 changes: 11 additions & 0 deletions doc/source/bibliography.bib
Original file line number Diff line number Diff line change
Expand Up @@ -179,4 +179,15 @@ @inproceedings{wurm2010octomap
volume={2},
pages={3},
year={2010}
}

@article{blanco2013robust,
title={A robust, multi-hypothesis approach to matching occupancy grid maps},
author={Blanco, Jose-Luis and Gonz{\'a}lez-Jim{\'e}nez, Javier and Fern{\'a}ndez-Madrigal, Juan-Antonio},
journal={Robotica},
volume={31},
number={5},
pages={687--701},
year={2013},
publisher={Cambridge University Press}
}
18 changes: 8 additions & 10 deletions libs/slam/include/mrpt/slam/CGridMapAligner.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,7 @@ namespace mrpt::slam
* 2D+orientation grid of possible 2D poses.
* - amRobustMatch: Detection of features + RANSAC matching
* - amModifiedRANSAC: Detection of features + modified multi-hypothesis
* RANSAC matching as described in was reported in the paper
* https://www.mrpt.org/Paper%3AOccupancy_Grid_Matching
* RANSAC matching as described in \cite blanco2013robust
*
* See CGridMapAligner::Align for more instructions.
*
Expand Down Expand Up @@ -66,7 +65,7 @@ class CGridMapAligner : public mrpt::slam::CMetricMapsAlignmentAlgorithm
std::ostream& out) const override; // See base docs

/** The aligner method: */
TAlignerMethod methodSelection{CGridMapAligner::amModifiedRANSAC};
TAlignerMethod methodSelection = CGridMapAligner::amModifiedRANSAC;

/** The feature descriptor to use: 0=detector already has descriptor, 1=
* SIFT, 2=SURF, 4=Spin images, 8=Polar images, 16=log-polar images */
Expand All @@ -89,22 +88,23 @@ class CGridMapAligner : public mrpt::slam::CMetricMapsAlignmentAlgorithm
/** [amRobustMatch method only] RANSAC-step options:
* \sa CICP::robustRigidTransformation
*/
float ransac_mahalanobisDistanceThreshold{6.0f};
float ransac_mahalanobisDistanceThreshold = 6.0f;

/** [amModifiedRANSAC method only] The quantile used for chi-square
* thresholding (default=0.99) */
double ransac_chi2_quantile{0.99};
double ransac_chi2_quantile = 0.99;

/** Probability of having a good inliers (def:0,9999), used for
* automatic number of iterations */
double ransac_prob_good_inliers{0.9999};
double ransac_prob_good_inliers = 0.9999999999;

/** Features extraction from grid map: How many features to extract */
float featsPerSquareMeter{0.015f};
/** Correspondences are considered if their distances are below this
* threshold (in the range [0,1]) (default=0.15). */
float threshold_max{0.15f};
/** Correspondences are considered if their distances to the best match
* are below this threshold (in the range [0,1]) (default=0.15). */
* are below this threshold (in the range [0,1]) (default=0.10). */
float threshold_delta{0.10f};

/** The minimum goodness (0-1) of the post-matching ICP to accept a
Expand All @@ -119,9 +119,7 @@ class CGridMapAligner : public mrpt::slam::CMetricMapsAlignmentAlgorithm
/** DEBUG - Dump all feature correspondences in a directory "grid_feats"
*/
bool save_feat_coors{false};
/** DEBUG - Show graphs with the details of each feature correspondences
*/
bool debug_show_corrs{false};

/** DEBUG - Save the pair of maps with all the pairings. */
bool debug_save_map_pairs{false};

Expand Down
11 changes: 0 additions & 11 deletions libs/slam/src/slam/CGridMapAligner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,15 +196,6 @@ CPosePDF::Ptr CGridMapAligner::AlignPDF_robustMatch(
const double thres_max = options.threshold_max;
const double thres_delta = options.threshold_delta;

// CDisplayWindowPlots::Ptr auxWin;
if (options.debug_show_corrs)
{
// auxWin = CDisplayWindowPlots::Ptr( new
// CDisplayWindowPlots("Individual corr.") );
std::cerr << "Warning: options.debug_show_corrs has no effect "
"since MRPT 0.9.1\n";
}

for (size_t idx1 = 0; idx1 < nLM1; idx1++)
{
// CVectorFloat corrs_indiv;
Expand Down Expand Up @@ -1112,7 +1103,6 @@ void CGridMapAligner::TConfigParams::dumpToTextStream(std::ostream& out) const
LOADABLEOPTS_DUMP_VAR(ransac_prob_good_inliers, double)
LOADABLEOPTS_DUMP_VAR(ransac_SOG_sigma_m, float)
LOADABLEOPTS_DUMP_VAR(save_feat_coors, bool)
LOADABLEOPTS_DUMP_VAR(debug_show_corrs, bool)
LOADABLEOPTS_DUMP_VAR(debug_save_map_pairs, bool)

LOADABLEOPTS_DUMP_VAR(feature_descriptor, int)
Expand Down Expand Up @@ -1152,7 +1142,6 @@ void CGridMapAligner::TConfigParams::loadFromConfigFile(
ransac_prob_good_inliers, double, iniFile, section)

MRPT_LOAD_CONFIG_VAR(save_feat_coors, bool, iniFile, section)
MRPT_LOAD_CONFIG_VAR(debug_show_corrs, bool, iniFile, section)
MRPT_LOAD_CONFIG_VAR(debug_save_map_pairs, bool, iniFile, section)

feature_descriptor = iniFile.read_enum(
Expand Down
1 change: 0 additions & 1 deletion python/src/mrpt/slam/COccupancyGridMapFeatureExtractor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,6 @@ void bind_mrpt_slam_COccupancyGridMapFeatureExtractor(std::function< pybind11::m
cl.def_readwrite("max_ICP_mahadist", &mrpt::slam::CGridMapAligner::TConfigParams::max_ICP_mahadist);
cl.def_readwrite("maxKLd_for_merge", &mrpt::slam::CGridMapAligner::TConfigParams::maxKLd_for_merge);
cl.def_readwrite("save_feat_coors", &mrpt::slam::CGridMapAligner::TConfigParams::save_feat_coors);
cl.def_readwrite("debug_show_corrs", &mrpt::slam::CGridMapAligner::TConfigParams::debug_show_corrs);
cl.def_readwrite("debug_save_map_pairs", &mrpt::slam::CGridMapAligner::TConfigParams::debug_save_map_pairs);
cl.def("loadFromConfigFile", (void (mrpt::slam::CGridMapAligner::TConfigParams::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::slam::CGridMapAligner::TConfigParams::loadFromConfigFile, "C++: mrpt::slam::CGridMapAligner::TConfigParams::loadFromConfigFile(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("source"), pybind11::arg("section"));
cl.def("assign", (class mrpt::slam::CGridMapAligner::TConfigParams & (mrpt::slam::CGridMapAligner::TConfigParams::*)(const class mrpt::slam::CGridMapAligner::TConfigParams &)) &mrpt::slam::CGridMapAligner::TConfigParams::operator=, "C++: mrpt::slam::CGridMapAligner::TConfigParams::operator=(const class mrpt::slam::CGridMapAligner::TConfigParams &) --> class mrpt::slam::CGridMapAligner::TConfigParams &", pybind11::return_value_policy::automatic, pybind11::arg(""));
Expand Down
1 change: 0 additions & 1 deletion python/stubs-out/mrpt/pymrpt/mrpt/slam.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ class CGridMapAligner(CMetricMapsAlignmentAlgorithm):

class TConfigParams(mrpt.pymrpt.mrpt.config.CLoadableOptions):
debug_save_map_pairs: bool
debug_show_corrs: bool
featsPerSquareMeter: float
feature_descriptor: mrpt.pymrpt.mrpt.vision.TDescriptorType
feature_detector_options: mrpt.pymrpt.mrpt.vision.CFeatureExtraction.TOptions
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ ransac_chi2_quantile = 0.5 // amModifiedRANSAC method only

save_feat_coors = 0 // Dump correspondences to grid_feats
debug_save_map_pairs = 1 // Save the pair of maps with the best correspondences
debug_show_corrs = 0 // Debug output of graphs


# All the params of the feature detectors/descriptors
Expand Down

0 comments on commit 0e53b10

Please sign in to comment.