struct mrpt::graphslam::deciders::CLoopCloserERD::TLaserParams¶
Struct for storing together the parameters needed for ICP matching, laser scans visualization etc.
#include <mrpt/graphslam/ERD/CLoopCloserERD.h> struct TLaserParams: public mrpt::config::CLoadableOptions { // fields mrpt::slam::CICP icp; int prev_nodes_for_ICP; const mrpt::img::TColor laser_scans_color = mrpt::img::TColor(0, 20, 255); bool visualize_laser_scans; std::string keystroke_laser_scans = "l"; bool use_scan_matching; bool has_read_config = false; TSlidingWindow mahal_distance_ICP_odom_win; TSlidingWindow goodness_threshold_win; // methods virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section); virtual void dumpToTextStream(std::ostream& out) const; };
Inherited Members¶
public: // methods virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section) = 0; void loadFromConfigFileName(const std::string& config_file, const std::string& section); virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const; void saveToConfigFileName(const std::string& config_file, const std::string& section) const; void dumpToConsole() const; virtual void dumpToTextStream(std::ostream& out) const;
Fields¶
int prev_nodes_for_ICP
How many nodes back to check ICP against?
const mrpt::img::TColor laser_scans_color = mrpt::img::TColor(0, 20, 255)
see Constructor for initialization
bool use_scan_matching
Indicate whethet to use scan-matching at all during graphSLAM [on by default].
It is strongly recomended that the user does not set this to false (via the .ini file). graphSLAM may diverge significantly if no scan-matching is not used.
TSlidingWindow mahal_distance_ICP_odom_win
Keep track of the mahalanobis distance between the initial pose difference and the suggested new edge for the pairs of checked nodes.
TSlidingWindow goodness_threshold_win
Keep track of ICP Goodness values for ICP between nearby nodes and adapt the Goodness threshold based on the median of the recorded Goodness values.
Methods¶
virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section)
This method load the options from a “.ini”-like file or memory-stored string list.
Only those parameters found in the given “section” and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an “.ini” file:
[section] resolution = 0.10 // blah blah... modeSelection = 1 // 0=blah, 1=blah,...
See also:
loadFromConfigFileName, saveToConfigFile
virtual void dumpToTextStream(std::ostream& out) const
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.