14 #include <mrpt/3rdparty/tclap/CmdLine.h> 54 TCLAP::SwitchArg arg_match(
55 "m",
"match",
"Operation: match two maps", cmd,
false);
56 TCLAP::SwitchArg arg_detect(
57 "d",
"detect-test",
"Operation: Quality of match with one map", cmd,
60 TCLAP::ValueArg<std::string> arg_filgrid1(
61 "1",
"map1",
"Map #1 to align (*.simplemap)",
true,
"",
62 "map1.simplemap", cmd);
63 TCLAP::ValueArg<std::string> arg_filgrid2(
64 "2",
"map2",
"Map #2 to align (*.simplemap)",
false,
"",
65 "map2.simplemap", cmd);
67 TCLAP::ValueArg<std::string> arg_out(
68 "o",
"out",
"Output file for the results",
false,
69 "gridmatching_out.txt",
"result_outfile", cmd);
70 TCLAP::ValueArg<std::string> arg_config(
71 "c",
"config",
"Optional config. file with more params",
false,
"",
74 TCLAP::ValueArg<std::string> arg_aligner_method(
75 "",
"aligner",
"The method to use for map aligning",
false,
76 "amModifiedRANSAC",
"[amCorrelation|amRobustMatch|amModifiedRANSAC]",
78 TCLAP::ValueArg<std::string> arg_out_dir(
79 "",
"out-dir",
"The output directory",
false,
"GRID-MATCHING_RESULTS",
80 "GRID-MATCHING_RESULTS", cmd);
82 TCLAP::SwitchArg arg_savesog3d(
83 "3",
"save-sog-3d",
"Save a 3D view of all the SOG modes", cmd,
false);
84 TCLAP::SwitchArg arg_savesogall(
85 "a",
"save-sog-all",
"Save all the map overlaps", cmd,
false);
86 TCLAP::SwitchArg arg_savecorrdists(
87 "t",
"save-corr-dists",
"Save corr & non-corr distances", cmd,
false);
88 TCLAP::ValueArg<std::string> arg_icpgoodness(
89 "i",
"save-icp-goodness",
"Append all ICP goodness values here",
false,
90 "",
"icp_goodness.txt", cmd);
92 TCLAP::ValueArg<double> arg_noise_std_xy(
93 "x",
"noise-std-xy",
"In detect-test mode,std. noise in XY",
false, 0,
95 TCLAP::ValueArg<double> arg_noise_std_phi(
96 "p",
"noise-std-phi",
"In detect-test mode,std. noise in PHI (deg)",
97 false, 0,
"sigma", cmd);
98 TCLAP::ValueArg<double> arg_noise_std_laser(
99 "l",
"noise-std-laser",
"In detect-test mode,std. noise range (m)",
100 false, 0,
"sigma", cmd);
101 TCLAP::ValueArg<unsigned int> arg_niters(
102 "N",
"iters",
"In detect-test mode,number of trials",
false, 1,
105 TCLAP::ValueArg<double> arg_Ax(
106 "X",
"Ax",
"In detect-test mode, displacement in X (m)",
false, 4,
"X",
108 TCLAP::ValueArg<double> arg_Ay(
109 "Y",
"Ay",
"In detect-test mode, displacement in Y (m)",
false, 2,
"Y",
111 TCLAP::ValueArg<double> arg_Aphi(
112 "P",
"Aphi",
"In detect-test mode, displacement in PHI (deg)",
false,
115 TCLAP::SwitchArg arg_noise_pose(
116 "O",
"noise-pose",
"detect-test mode: enable noise in pose", cmd,
118 TCLAP::SwitchArg arg_noise_laser(
119 "L",
"noise-laser",
"detect-test mode: enable noise in laser", cmd,
122 TCLAP::SwitchArg arg_verbose(
"v",
"verbose",
"Verbose output", cmd,
false);
123 TCLAP::SwitchArg arg_nologo(
124 "g",
"nologo",
"skip the logo at startup", cmd,
false);
125 TCLAP::SwitchArg arg_nosave(
126 "n",
"nosave",
"skip saving map images", cmd,
false);
127 TCLAP::SwitchArg arg_skip_icp(
128 "s",
"noicp",
"skip ICP optimization stage", cmd,
false);
129 TCLAP::SwitchArg arg_most_likely(
130 "",
"most-likely-only",
131 "Keep the most-likely Gaussian mode from the SOG", cmd,
false);
150 N_ITERS = arg_niters.getValue();
152 GT_Ax = arg_Ax.getValue();
153 GT_Ay = arg_Ay.getValue();
159 NOSAVE = arg_nosave.getValue();
162 if (!arg_nologo.getValue())
164 printf(
" grid-matching - Part of the MRPT\n");
166 " MRPT C++ Library: %s - Sources timestamp: %s\n",
184 std::cerr << std::endl
185 <<
"Error: One operation mode 'match' or 'detect-test' or " 186 "'save-corr-dists' must be selected." 196 if (!arg_filgrid1.isSet() || !arg_filgrid2.isSet())
198 std::cerr << std::endl
199 <<
"Error: Two maps must be passed: --map1=xxx and " 240 if (ext1 != ext2 || ext1 !=
"simplemap")
250 if (ext1 !=
"simplemap")
284 "%% std_noise_xy std_noise_phi std_noise_laser covDet:mean&std " 285 "stdPhi:mean&std error2D:mean&std errorPhi:mean&phi " 286 "bruteErr2D:mean&std brutErrPhi:mean&std GT_likelihood " 287 "#GTcorrFound:mean&std \n");
288 f_log.
printf(
"%% -----------------------------------------\n");
311 map2_inits = map1_inits;
372 grid1->saveAsBitmapFileWithLandmarks(
375 grid1->getAsImageFiltered(img);
384 std::vector<uint32_t> overallGTcorrsFound;
386 for (
unsigned int iter = 0; iter <
N_ITERS; iter++)
392 for (
unsigned int q = 0; q < map2noisy.
size(); q++)
397 map2noisy.
get(q, PDF, SF);
405 PDF->changeCoordinatesReference(
CPose3D(gt));
414 for (
unsigned int k = 0; k < obs->getScanSize(); k++)
416 float& v = obs->getScanRange(k);
427 std::make_shared<CPosePDFGaussian>();
428 newPDF->copyFrom(*PDF);
437 newPDF->mean.normalizePhi();
462 grid2->saveAsBitmapFile(
format(
464 grid2->saveAsBitmapFileWithLandmarks(
470 grid2->getAsImageFiltered(img);
484 &the_map1, &the_map2,
CPose2D(0, 0, 0), info);
491 pdf_SOG->getMostLikelyCovarianceAndMean(
502 float stdXY = sqrt(estimateCOV22.det());
524 partsPdf->saveToTextFile(
format(
525 "%s/particles_noise_%.03f.txt",
RESULTS_DIR.c_str(),
529 "Goodness: %.03f%%\n", 100 * info.
goodness);
531 partsPdf->particlesCount() <<
" particles");
539 "SoG has %u modes.", (
unsigned int)pdf_SOG->size());
541 pdf_SOG->normalizeWeights();
544 stats_GT_likelihood.
push_back((
float)pdf_SOG->evaluatePDF(
549 f_out_log.
printf(
"%% SOG_log_w x y phi \n");
550 for (
size_t m = 0; m < pdf_SOG->size(); m++)
552 " %e %f %f %f\n", pdf_SOG->get(m).log_w,
553 pdf_SOG->get(m).mean.x(),
554 pdf_SOG->get(m).mean.y(),
555 pdf_SOG->get(m).mean.phi());
562 std::make_shared<opengl::CSetOfObjects>();
563 pdf_SOG->getAs3DObject(thePDF3D);
565 std::make_shared<opengl::CGridPlaneXY>(
566 -10, 10, -10, 10, 0, 1);
584 CImage imgGrid1, imgCanvas;
586 min(grid1->getXMin(), -60.0f),
587 max(grid1->getXMax(), 60.0f),
588 min(-40.0f, grid1->getYMin()),
589 max(30.0f, grid1->getYMax()));
590 grid1->getAsImage(imgGrid1,
true);
592 const CPose2D nullPose(0, 0, 0);
594 const TPoint2D q1(grid1->getXMin(), grid1->getYMin());
595 const TPoint2D q2(grid1->getXMin(), grid1->getYMax());
596 const TPoint2D q3(grid1->getXMax(), grid1->getYMax());
597 const TPoint2D q4(grid1->getXMax(), grid1->getYMin());
599 const TPoint2D p1(grid2->getXMin(), grid2->getYMin());
600 const TPoint2D p2(grid2->getXMin(), grid2->getYMax());
601 const TPoint2D p3(grid2->getXMax(), grid2->getYMax());
602 const TPoint2D p4(grid2->getXMax(), grid2->getYMin());
603 for (nNode = 0, it = pdf_SOG->begin();
604 it != pdf_SOG->end(); it++, nNode++)
613 imgCanvas = imgGrid1;
618 imgGrid1LY - 1 - grid1->y2idx(pp1.
y),
620 imgGrid1LY - 1 - grid1->y2idx(pp2.
y),
624 imgGrid1LY - 1 - grid1->y2idx(pp2.
y),
626 imgGrid1LY - 1 - grid1->y2idx(pp3.
y),
630 imgGrid1LY - 1 - grid1->y2idx(pp3.
y),
632 imgGrid1LY - 1 - grid1->y2idx(pp4.
y),
636 imgGrid1LY - 1 - grid1->y2idx(pp4.
y),
638 imgGrid1LY - 1 - grid1->y2idx(pp1.
y),
642 "%s/_OVERLAP_MAPS_SOG_MODE_%04u.png",
648 std::make_shared<CSetOfObjects>();
651 std::make_shared<CSetOfObjects>();
661 std::make_shared<CSetOfLines>();
662 lines->setLineWidth(3);
663 lines->setColor(0, 0, 1);
665 lines->appendLine(q1.x, q1.y, 0, q2.x, q2.y, 0);
666 lines->appendLine(q2.x, q2.y, 0, q3.x, q3.y, 0);
667 lines->appendLine(q3.x, q3.y, 0, q4.x, q4.y, 0);
668 lines->appendLine(q4.x, q4.y, 0, q1.x, q1.y, 0);
670 lines->appendLine(pp1.
x, pp1.
y, 0, pp2.
x, pp2.
y, 0);
671 lines->appendLine(pp2.
x, pp2.
y, 0, pp3.
x, pp3.
y, 0);
672 lines->appendLine(pp3.
x, pp3.
y, 0, pp4.
x, pp4.
y, 0);
673 lines->appendLine(pp4.
x, pp4.
y, 0, pp1.
x, pp1.
y, 0);
678 "%s/_OVERLAP_MAPS_SOG_MODE_%04u.3Dscene",
692 "%s/SOG_grid_limits_noise_%f.txt",
RESULTS_DIR.c_str(),
696 pdf_SOG->evaluatePDFInArea(
697 gridLimits(0, 0), gridLimits(0, 1), gridLimits(0, 2),
698 gridLimits(0, 3), 0.002f, 0, evalGrid,
714 stats_bruteErrorPhi.
push_back(AphiBrute);
725 const bool SAVE_ALSO_COORS_DEBUG_MAPS =
false;
731 if (!lmap1 && !lmap2)
733 lmap1 = CLandmarksMap::Create();
734 lmap2 = CLandmarksMap::Create();
756 for (
size_t i1 = 0; i1 < lmap1->landmarks.size(); i1++)
764 const CLandmark* l1 = lmap1->landmarks.get(i1);
766 for (i2 = 0; i2 < lmap2->landmarks.size(); i2++)
768 CLandmark* l2 = lmap2->landmarks.get(i2);
779 D[i2] = l1->
features[0].descriptorDistanceTo(
783 size_t best_match = 0;
784 dErrs.minCoeff(best_match);
786 if (dErrs[best_match] < 0.20)
788 CLandmark* l2 = lmap2->landmarks.get(best_match);
795 best_match = (
unsigned int)(-1);
801 for (i2 = 0; i2 < lmap2->landmarks.size(); i2++)
803 if (i2 == best_match)
805 "%f %f\n", D[i2], D[i2] - MIN_DESCR_DIST);
808 "%f %f\n", D[i2], D[i2] - MIN_DESCR_DIST);
815 overallGTcorrsFound.push_back(gt_corrs.size());
816 if (SAVE_ALSO_COORS_DEBUG_MAPS)
818 COccupancyGridMap2D::saveAsBitmapTwoMapsWithCorrespondences(
819 "GT_corrs.png", grid1.get(), grid2.get(), gt_corrs);
827 "%f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %e %f %f\n",
This CStream derived class allow using a file as a read/write binary stream, creating it if the file ...
A namespace of pseudo-random numbers generators of diferent distributions.
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
mrpt::poses::CPosePDF::Ptr Align(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt)
The method for aligning a pair of metric maps, for SE(2) relative poses.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
void line(int x0, int y0, int x1, int y1, const mrpt::img::TColor color, unsigned int width=1, TPenStyle penStyle=psSolid) override
Draws a line.
bool SAVE_SOG_ALL_MAPS_OVERLAP_HYPOTHESES
bool createDirectory(const std::string &dirName)
Creates a directory.
This class is a "CSerializable" wrapper for "CMatrixDynamic<double>".
mrpt::poses::CPose2D estimateMean
mrpt::maps::COccupancyGridMap2D::TInsertionOptions insertionOpts
Observations insertion options.
void loadFromProbabilisticPosesAndObservations(const mrpt::maps::CSimpleMap &Map)
Load the map contents from a CSimpleMap object, erasing all previous content of the map...
Template for column vectors of dynamic size, compatible with Eigen.
#define THROW_EXCEPTION(msg)
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
A class for aligning two multi-metric maps (with an occupancy grid maps and a points map...
std::string std::string format(std::string_view fmt, ARGS &&... args)
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
mrpt::img::TColorf color
Color of points.
bool fileOpenCorrectly() const
Returns true if the file was open without errors.
double stddev(const VECTORLIKE &v, bool unbiased=true)
Computes the standard deviation of a vector.
void randomize(const uint32_t seed)
Initialize the PRNG from the given random seed.
This class allows loading and storing values and vectors of different types from ".ini" files easily.
This file implements several operations that operate element-wise on individual or pairs of container...
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
mrpt::maps::CPointsMap::TRenderOptions renderOpts
Rendering as 3D object options.
void setMinLoggingLevel(const VerbosityLevel level)
Set the minimum logging level for which the incoming logs are going to be taken into account...
size_t getHeight() const override
Returns the height of the image in pixels.
std::string MRPT_getCompilationDate()
Returns the MRPT source code timestamp, according to the Reproducible-Builds specifications: https://...
mrpt::system::COutputLogger COutputLogger
T::Ptr mapByClass(size_t ith=0) const
Returns the i'th map of a given class (or of a derived class), or empty smart pointer if there is no ...
The ICP algorithm return information.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
void saveToTextFile(const std::string &file, mrpt::math::TMatrixTextFileFormat fileFormat=mrpt::math::MATRIX_FORMAT_ENG, bool appendMRPTHeader=false, const std::string &userHeader=std::string()) const
Saves the vector/matrix to a file compatible with MATLAB/Octave text format.
void push_back(const T &val)
CMatrixFixed< Scalar, BLOCK_ROWS, BLOCK_COLS > extractMatrix(const int start_row=0, const int start_col=0) const
double distanceTo(const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
Returns the Euclidean distance to another pose/point:
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream, std::istream, std::ostream, std::stringstream.
VerbosityLevel getMinLoggingLevel() const
#define ASSERT_(f)
Defines an assertion mechanism.
CListGaussianModes::iterator iterator
This base provides a set of functions for maths stuff.
void initialize(int argc, const char **argv)
Initializes the application from CLI parameters.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::vision::TDescriptorType feature_descriptor
The feature descriptor to use: 0=detector already has descriptor, 1= SIFT, 2=SURF, 4=Spin images, 8=Polar images, 16=log-polar images.
A class for storing a map of 3D probabilistic landmarks.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ionName) override
Loads the configuration for the set of internal maps from a textual definition in an INI-like file...
double phi() const
Get the phi angle of the 2D pose (in radians)
constexpr double DEG2RAD(const double x)
Degrees to radians.
mrpt::maps::CPointsMap::TInsertionOptions insertionOpts
Observations insertion options.
mrpt::vision::CFeatureExtraction::TOptions feature_detector_options
All the parameters for the feature detector.
mrpt::math::CMatrixDouble33 estimateCOV
void deleteFiles(const std::string &s)
Delete one or more files, especified by the (optional) path and the file name (including '...
This namespace contains representation of robot actions and observations.
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
bool sectionExists(const std::string §ion_name) const
Checks if a given section exists (name is case insensitive)
std::string extractFileExtension(const std::string &filePath, bool ignore_gz=false)
Extract the extension of a filename.
double x() const
Common members of all points & poses classes.
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x...
void set(size_t index, const mrpt::poses::CPose3DPDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF)
Changes the i'th pair, first one is index '0'.
size_t size() const
Returns the count of pairs (pose,sensory data)
float maxDistanceInsertion
The largest distance at which cells will be updated (Default 15 meters)
return_t drawGaussian1D(const double mean, const double std)
Generate a normally distributed pseudo-random number.
void get(size_t index, mrpt::poses::CPose3DPDF::Ptr &out_posePDF, mrpt::obs::CSensoryFrame::Ptr &out_SF) const
Access to the i'th pair, first one is index '0'.
This CStream derived class allow using a file as a write-only, binary stream.
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
float ransac_SOG_sigma_m
The square root of the uncertainty normalization variance var_m (see papers...)
A class used to store a 2D point.
bool open(const std::string &fileName, TFileOpenModes mode=fomRead|fomWrite)
Opens the file, returning true on success.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
bool saveToFile(const std::string &fil) const
Saves the scene to a 3Dscene file, loadable by the application SceneViewer3D.
float goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
void pause(const std::string &msg=std::string("Press any key to continue...")) noexcept
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
void run()
Runs with the current parameter set.
void push_back(const MAP_DEFINITION &o)
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
CONTAINER::Scalar minimum(const CONTAINER &v)
mrpt::maps::CLandmarksMap::Ptr landmarks_map1
The landmarks of each map (the indices of these landmarks correspond to those in "correspondences") ...
A class for storing an occupancy grid map.
std::vector< double > icp_goodness_all_sog_modes
The ICP goodness of all potential SOG modes at the stage "sog2", thus before the removing of "bad" IC...
mrpt::slam::CGridMapAligner::TAlignerMethod aligner_method
This class is a "CSerializable" wrapper for "CMatrixFloat".
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
The class for storing "landmarks" (visual or laser-scan-extracted features,...)
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool SAVE_CORR_AND_NONCORR_DISTS
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
double distance2DTo(double ax, double ay) const
Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
An RGBA color - floats in the range [0,1].
std::vector< mrpt::vision::CFeature > features
The set of features from which the landmark comes.
The namespace for 3D scene representation and rendering.
double mean(const CONTAINER &v)
Computes the mean value of a vector.
float featsPerSquareMeter
Features extraction from grid map: How many features to extract.
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
TAlignerMethod methodSelection
The aligner method:
mrpt::slam::CGridMapAligner::TConfigParams options
mrpt::maps::CLandmarksMap::Ptr landmarks_map2
Classes for creating GUI windows for 2D and 3D visualization.
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)...
float maxOccupancyUpdateCertainty
A value in the range [0.5,1] used for updating cell with a bayesian approach (default 0...
std::string MRPT_getVersion()
Returns a string describing the MRPT version.
bool vectorToTextFile(const std::vector< float > &vec, const std::string &fileName, bool append=false, bool byRows=false)
A useful function for debugging, which saves a std::vector into a text file (compat.
mrpt::math::TPoint3D pose_mean
The mean of the landmark 3D position.
This class stores any customizable set of metric maps.
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
void insert(const CRenderizable::Ptr &newObject, const std::string &viewportName=std::string("main"))
Insert a new object into the scene, in the given viewport (by default, into the "main" viewport)...
mrpt::poses::CPose2D noRobustEstimation
The "brute" estimation from using all the available correspondences, provided just for comparison pur...
void dumpToConsole() const
Just like dumpToTextStream() but sending the text to the console (std::cout)
Functions for estimating the optimal transformation between two frames of references given measuremen...
std::string SAVE_ICP_GOODNESS_FIL
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
bool MOST_LIKELY_SOG_MODE_ONLY
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &init)
Sets the list of internal map according to the passed list of map initializers (current maps will be ...
A class for storing images as grayscale or RGB bitmaps.
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
int round(const T value)
Returns the closer integer (int) to x.