Class CMetricMapBuilderICP
Defined in File CMetricMapBuilderICP.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public mrpt::slam::CMetricMapBuilder(Class CMetricMapBuilder)
Class Documentation
-
class CMetricMapBuilderICP : public mrpt::slam::CMetricMapBuilder
A class for very simple 2D SLAM based on ICP. This is a non-probabilistic pose tracking algorithm. Map are stored as in files as binary dumps of “mrpt::maps::CSimpleMap” objects. The methods are thread-safe.
Public Functions
-
CMetricMapBuilderICP()
Default constructor - Upon construction, you can set the parameters in ICP_options, then call “initialize”.
-
~CMetricMapBuilderICP() override
Destructor:
-
virtual void initialize(const mrpt::maps::CSimpleMap &initialMap = mrpt::maps::CSimpleMap(), const mrpt::poses::CPosePDF *x0 = nullptr) override
Initialize the method, starting with a known location PDF “x0”(if supplied, set to nullptr to left unmodified) and a given fixed, past map. This method MUST be called if using the default constructor, after loading the configuration into ICP_options. In particular, TConfigParams::mapInitializers
-
virtual mrpt::poses::CPose3DPDF::Ptr getCurrentPoseEstimation() const override
Returns a copy of the current best pose estimation as a pose PDF.
-
void setCurrentMapFile(const char *mapFile)
Sets the “current map file”, thus that map will be loaded if it exists or a new one will be created if it does not, and the updated map will be save to that file when destroying the object.
-
virtual void processActionObservation(mrpt::obs::CActionCollection &action, mrpt::obs::CSensoryFrame &in_SF) override
Appends a new action and observations to update this map: See the description of the class at the top of this page to see a more complete description.
See also
- Parameters:
action – The estimation of the incremental pose change in the robot pose.
in_SF – The set of observations that robot senses at the new pose. See params in CMetricMapBuilder::options and CMetricMapBuilderICP::ICP_options
-
void processObservation(const mrpt::obs::CObservation::Ptr &obs)
The main method of this class: Process one odometry or sensor observation. The new entry point of the algorithm (the old one was processActionObservation, which now is a wrapper to this method). See params in CMetricMapBuilder::options and CMetricMapBuilderICP::ICP_options
-
virtual void getCurrentlyBuiltMap(mrpt::maps::CSimpleMap &out_map) const override
Fills “out_map” with the set of “poses”-“sensory-frames”, thus the so far built map
-
void getCurrentMapPoints(std::vector<float> &x, std::vector<float> &y)
Returns the 2D points of current local map
-
virtual const mrpt::maps::CMultiMetricMap &getCurrentlyBuiltMetricMap() const override
Returns the map built so far. NOTE that for efficiency a pointer to the internal object is passed, DO NOT delete nor modify the object in any way, if desired, make a copy of ir with “clone()”.
-
virtual unsigned int getCurrentlyBuiltMapSize() override
Returns just how many sensory-frames are stored in the currently build map
-
virtual void saveCurrentEstimationToImage(const std::string &file, bool formatEMF_BMP = true) override
A useful method for debugging: the current map (and/or poses) estimation is dumped to an image file.
- Parameters:
file – The output file name
formatEMF_BMP – Output format = true:EMF, false:BMP
Public Members
-
TConfigParams ICP_options
Options for the ICP-SLAM application
See also
-
CICP::TConfigParams ICP_params
Options for the ICP algorithm itself
See also
-
struct TConfigParams : public mrpt::config::CLoadableOptions
Algorithm configuration params
Public Functions
-
TConfigParams(mrpt::system::VerbosityLevel &parent_verbosity_level)
Initializer
-
TConfigParams &operator=(const TConfigParams &other)
-
inline TConfigParams(const TConfigParams &other)
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
void dumpToTextStream(std::ostream &out) const override
Public Members
-
bool matchAgainstTheGrid
(default:false) Match against the occupancy grid or the points map? The former is quicker but less precise.
-
double insertionLinDistance
Minimum robot linear (m) displacement for a new observation to be inserted in the map.
-
double insertionAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be inserted in the map.
-
double localizationLinDistance
Minimum robot linear (m) displacement for a new observation to be used to do ICP-based localization (otherwise, dead-reckon with odometry).
-
double localizationAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be used to do ICP-based localization (otherwise, dead-reckon with odometry).
-
double minICPgoodnessToAccept
Minimum ICP goodness (0,1) to accept the resulting corrected position (default: 0.40)
-
mrpt::system::VerbosityLevel &verbosity_level
-
mrpt::maps::TSetOfMetricMapInitializers mapInitializers
What maps to create (at least one points map and/or a grid map are needed). For the expected format in the .ini file when loaded with loadFromConfigFile(), see documentation of TSetOfMetricMapInitializers.
-
TConfigParams(mrpt::system::VerbosityLevel &parent_verbosity_level)
-
CMetricMapBuilderICP()