MRPT  2.0.4
List of all members | Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Attributes | Private Member Functions | Private Attributes
mrpt::slam::CGridMapAligner Class Reference

Detailed Description

A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching.

The matching pose is returned as a Sum of Gaussians (poses::CPosePDFSOG).

This class can use three methods (see options.methodSelection):

See CGridMapAligner::Align for more instructions.

See also
CMetricMapsAlignmentAlgorithm

Definition at line 40 of file CGridMapAligner.h.

#include <mrpt/slam/CGridMapAligner.h>

Inheritance diagram for mrpt::slam::CGridMapAligner:

Classes

class  TConfigParams
 The ICP algorithm configuration data. More...
 
struct  TReturnInfo
 The ICP algorithm return information. More...
 

Public Types

enum  TAlignerMethod { amRobustMatch = 0, amCorrelation, amModifiedRANSAC }
 The type for selecting the grid-map alignment algorithm. More...
 

Public Member Functions

 CGridMapAligner ()
 
mrpt::poses::CPosePDF::Ptr AlignPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt) override
 The method for aligning a pair of 2D points map. More...
 
mrpt::poses::CPose3DPDF::Ptr Align3DPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt) override
 Not applicable in this class, will launch an exception if used. More...
 
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. More...
 
mrpt::poses::CPose3DPDF::Ptr Align3D (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3D &grossEst, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt)
 

Static Public Member Functions

static std::array< mrpt::system::TConsoleColor, NUMBER_OF_VERBOSITY_LEVELS > & logging_levels_to_colors ()
 Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor. More...
 
static std::array< std::string, NUMBER_OF_VERBOSITY_LEVELS > & logging_levels_to_names ()
 Map from VerbosityLevels to their corresponding names. More...
 

Public Attributes

mrpt::slam::CGridMapAligner::TConfigParams options
 

Protected Attributes

VerbosityLevel m_min_verbosity_level {LVL_INFO}
 Provided messages with VerbosityLevel smaller than this value shall be ignored. More...
 

Private Member Functions

mrpt::poses::CPosePDF::Ptr AlignPDF_correlation (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &info)
 Private member, implements one the algorithms. More...
 
mrpt::poses::CPosePDF::Ptr AlignPDF_robustMatch (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &info)
 Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms. More...
 

Private Attributes

COccupancyGridMapFeatureExtractor m_grid_feat_extr
 Grid map features extractor. More...
 

Logging methods

bool logging_enable_console_output {true}
 [Default=true] Set it to false in case you don't want the logged messages to be dumped to the output automatically. More...
 
bool logging_enable_keep_record {false}
 [Default=false] Enables storing all messages into an internal list. More...
 
void logStr (const VerbosityLevel level, std::string_view msg_str) const
 Main method to add the specified message string to the logger. More...
 
void logFmt (const VerbosityLevel level, const char *fmt,...) const MRPT_printf_format_check(3
 Alternative logging method, which mimics the printf behavior. More...
 
void void logCond (const VerbosityLevel level, bool cond, const std::string &msg_str) const
 Log the given message only if the condition is satisfied. More...
 
void setLoggerName (const std::string &name)
 Set the name of the COutputLogger instance. More...
 
std::string getLoggerName () const
 Return the name of the COutputLogger instance. More...
 
void setMinLoggingLevel (const VerbosityLevel level)
 Set the minimum logging level for which the incoming logs are going to be taken into account. More...
 
void setVerbosityLevel (const VerbosityLevel level)
 alias of setMinLoggingLevel() More...
 
VerbosityLevel getMinLoggingLevel () const
 
bool isLoggingLevelVisible (VerbosityLevel level) const
 
void getLogAsString (std::string &log_contents) const
 Fill the provided string with the contents of the logger's history in std::string representation. More...
 
std::string getLogAsString () const
 Get the history of COutputLogger instance in a string representation. More...
 
void writeLogToFile (const std::string *fname_in=nullptr) const
 Write the contents of the COutputLogger instance to an external file. More...
 
void dumpLogToConsole () const
 Dump the current contents of the COutputLogger instance in the terminal window. More...
 
std::string getLoggerLastMsg () const
 Return the last Tmsg instance registered in the logger history. More...
 
void getLoggerLastMsg (std::string &msg_str) const
 Fill inputtted string with the contents of the last message in history. More...
 
void loggerReset ()
 Reset the contents of the logger instance. More...
 
void logRegisterCallback (output_logger_callback_t userFunc)
 
bool logDeregisterCallback (output_logger_callback_t userFunc)
 

Member Enumeration Documentation

◆ TAlignerMethod

The type for selecting the grid-map alignment algorithm.

Enumerator
amRobustMatch 
amCorrelation 
amModifiedRANSAC 

Definition at line 46 of file CGridMapAligner.h.

Constructor & Destructor Documentation

◆ CGridMapAligner()

mrpt::slam::CGridMapAligner::CGridMapAligner ( )
inline

Definition at line 43 of file CGridMapAligner.h.

Member Function Documentation

◆ Align()

CPosePDF::Ptr CMetricMapsAlignmentAlgorithm::Align ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose2D grossEst,
mrpt::optional_ref< TMetricMapAlignmentResult outInfo = std::nullopt 
)
inherited

The method for aligning a pair of metric maps, for SE(2) relative poses.

The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look at the derived classes for instructions. The target is to find a PDF for the pose displacement between maps, thus the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.

Parameters
m1[IN] The first map
m2[IN] The second map. The pose of this map respect to m1 is to be estimated.
grossEst[IN] An initial gross estimation for the displacement. If a given algorithm doesn't need it, set to CPose2D(0,0,0) for example.
runningTime[OUT] A pointer to a container for obtaining the algorithm running time in seconds, or nullptr if you don't need it.
info[OUT] See derived classes for details, or nullptr if it isn't needed.
Returns
A smart pointer to the output estimated pose PDF.
See also
CICP

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Returns
A smart pointer to the output estimated pose PDF.
See also
CICP

Definition at line 22 of file CMetricMapsAlignmentAlgorithm.cpp.

Referenced by ICPTests::align2scans(), mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::slam::CMetricMapBuilderICP::processObservation(), and mrpt::apps::CGridMapAlignerApp::run().

Here is the caller graph for this function:

◆ Align3D()

CPose3DPDF::Ptr CMetricMapsAlignmentAlgorithm::Align3D ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose3D grossEst,
mrpt::optional_ref< TMetricMapAlignmentResult outInfo = std::nullopt 
)
inherited

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Returns
A smart pointer to the output estimated pose PDF.
See also
CICP

Definition at line 31 of file CMetricMapsAlignmentAlgorithm.cpp.

References mrpt::poses::CPose3DPDFGaussian::mean.

Referenced by TEST_F().

Here is the caller graph for this function:

◆ Align3DPDF()

CPose3DPDF::Ptr CGridMapAligner::Align3DPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose3DPDFGaussian initialEstimationPDF,
mrpt::optional_ref< TMetricMapAlignmentResult outInfo = std::nullopt 
)
overridevirtual

Not applicable in this class, will launch an exception if used.

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

Definition at line 1163 of file CGridMapAligner.cpp.

References THROW_EXCEPTION.

◆ AlignPDF()

CPosePDF::Ptr CGridMapAligner::AlignPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
mrpt::optional_ref< TMetricMapAlignmentResult outInfo = std::nullopt 
)
overridevirtual

The method for aligning a pair of 2D points map.

The meaning of some parameters are implementation dependant, so look for derived classes for instructions. The target is to find a PDF for the pose displacement between maps, thus the pose of m2 relative to m1. This pose is returned as a PDF rather than a single value.

NOTE: This method can be configurated with "options"

Parameters
m1[IN] The first map (Must be a mrpt::maps::CMultiMetricMap class)
m2[IN] The second map (Must be a mrpt::maps::CMultiMetricMap class)
initialEstimationPDF[IN] (IGNORED IN THIS ALGORITHM!)
runningTime[OUT] A pointer to a container for obtaining the algorithm running time in seconds, or NULL if you don't need it.
info[OUT] A pointer to a TReturnInfo struct, or NULL if result information are not required.
Note
The returned PDF depends on the selected alignment method:
  • "amRobustMatch" –> A "poses::CPosePDFSOG" object.
  • "amCorrelation" –> A "poses::CPosePDFGrid" object.
Returns
A smart pointer to the output estimated pose PDF.
See also
CPointsMapAlignmentAlgorithm, options

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

Definition at line 41 of file CGridMapAligner.cpp.

References MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ AlignPDF_correlation()

CPosePDF::Ptr CGridMapAligner::AlignPDF_correlation ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
TReturnInfo info 
)
private

◆ AlignPDF_robustMatch()

CPosePDF::Ptr CGridMapAligner::AlignPDF_robustMatch ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
TReturnInfo info 
)
private

Private member, implements both, the "robustMatch" and the newer "modifiedRANSAC" algorithms.

Definition at line 85 of file CGridMapAligner.cpp.

References ASSERT_, ASSERTMSG_, mrpt::math::chi2inv(), mrpt::slam::CGridMapAligner::TReturnInfo::correspondences, mrpt::slam::CGridMapAligner::TReturnInfo::correspondences_dists_maha, mrpt::maps::CMultiMetricMap::countMapsByClass(), mrpt::poses::CPoint2DPDFGaussian::cov, mrpt::poses::CPosePDFSOG::TGaussianMode::cov, mrpt::poses::CPosePDFGaussian::cov, mrpt::system::createDirectory(), mrpt::system::deleteFilesInDirectory(), mrpt::math::distanceBetweenPoints(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distanceTo(), mrpt::img::CImage::drawImage(), mrpt::random::CRandomGenerator::drawUniform32bit(), mrpt::slam::TMetricMapAlignmentResult::executionTime, mrpt::img::CCanvas::filledRectangle(), mrpt::format(), mrpt::maps::COccupancyGridMap2D::getArea(), mrpt::img::CImage::getHeight(), mrpt::maps::CPointsMap::getPoint(), mrpt::random::getRandomGenerator(), mrpt::maps::COccupancyGridMap2D::getResolution(), mrpt::maps::COccupancyGridMap2D::getSizeX(), mrpt::maps::COccupancyGridMap2D::getSizeY(), mrpt::img::CImage::getWidth(), mrpt::slam::CGridMapAligner::TReturnInfo::goodness, mrpt::slam::CICP::TReturnInfo::goodness, mrpt::slam::CGridMapAligner::TReturnInfo::icp_goodness_all_sog_modes, mrpt::maps::CPointsMap::insertPoint(), IS_CLASS, mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint2DIdx(), mrpt::slam::CGridMapAligner::TReturnInfo::landmarks_map1, mrpt::slam::CGridMapAligner::TReturnInfo::landmarks_map2, mrpt::tfest::TSE2RobustResult::largestSubSet, mrpt::poses::CPosePDFSOG::TGaussianMode::log_w, mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPosePDFGaussian::mahalanobisDistanceTo(), mrpt::maps::CMultiMetricMap::mapByClass(), mrpt::poses::CPoint2DPDFGaussian::mean, mrpt::poses::CPosePDFGaussian::mean, mrpt::poses::CPosePDFSOG::TGaussianMode::mean, mrpt::math::mean(), mrpt::math::minimum(), MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_INFO, MRPT_LOG_INFO_FMT, MRPT_LOG_INFO_STREAM, MRPT_START, mrpt::math::multiply_HCHt(), myVectorOrder(), mrpt::slam::CGridMapAligner::TReturnInfo::noRobustEstimation, mrpt::tfest::TMatchingPair::other_idx, mrpt::tfest::TMatchingPair::other_x, mrpt::tfest::TMatchingPair::other_y, mrpt::tfest::TMatchingPair::other_z, mrpt::poses::CPose2D::phi(), mrpt::tfest::TSE2RobustParams::probability_find_good_model, mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), mrpt::RAD2DEG(), mrpt::tfest::TSE2RobustParams::ransac_algorithmForLandmarks, mrpt::tfest::TSE2RobustParams::ransac_fuseByCorrsMatch, mrpt::tfest::TSE2RobustParams::ransac_fuseMaxDiffPhi, mrpt::tfest::TSE2RobustParams::ransac_fuseMaxDiffXY, mrpt::tfest::TSE2RobustParams::ransac_mahalanobisDistanceThreshold, mrpt::tfest::TSE2RobustParams::ransac_maxSetSize, mrpt::tfest::TSE2RobustParams::ransac_minSetSize, mrpt::tfest::TSE2RobustParams::ransac_nSimulations, mrpt::maps::CSimplePointsMap::reserve(), mrpt::round(), mrpt::img::CImage::saveToFile(), mrpt::tfest::se2_l2(), mrpt::tfest::se2_l2_robust(), mrpt::slam::CGridMapAligner::TReturnInfo::sog1, mrpt::slam::CGridMapAligner::TReturnInfo::sog2, mrpt::slam::CGridMapAligner::TReturnInfo::sog3, mrpt::square(), mrpt::system::CTicTac::Tac(), mrpt::tfest::TMatchingPair::this_idx, mrpt::tfest::TMatchingPair::this_x, mrpt::tfest::TMatchingPair::this_y, mrpt::tfest::TMatchingPair::this_z, THROW_EXCEPTION, mrpt::system::CTicTac::Tic(), mrpt::tfest::TSE2RobustResult::transformation, mrpt::tfest::TSE2RobustParams::verbose, win, mrpt::math::TPoint2D_data< T >::x, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), mrpt::math::TPoint2D_data< T >::y, and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().

Here is the call graph for this function:

◆ dumpLogToConsole()

void COutputLogger::dumpLogToConsole ( ) const
inherited

Dump the current contents of the COutputLogger instance in the terminal window.

See also
writeToFile

Definition at line 190 of file COutputLogger.cpp.

◆ getLogAsString() [1/2]

void COutputLogger::getLogAsString ( std::string &  log_contents) const
inherited

Fill the provided string with the contents of the logger's history in std::string representation.

Definition at line 154 of file COutputLogger.cpp.

◆ getLogAsString() [2/2]

std::string COutputLogger::getLogAsString ( ) const
inherited

Get the history of COutputLogger instance in a string representation.

Definition at line 159 of file COutputLogger.cpp.

Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport().

Here is the caller graph for this function:

◆ getLoggerLastMsg() [1/2]

std::string COutputLogger::getLoggerLastMsg ( ) const
inherited

Return the last Tmsg instance registered in the logger history.

Definition at line 195 of file COutputLogger.cpp.

References mrpt::system::COutputLogger::TMsg::getAsString().

Here is the call graph for this function:

◆ getLoggerLastMsg() [2/2]

void COutputLogger::getLoggerLastMsg ( std::string &  msg_str) const
inherited

Fill inputtted string with the contents of the last message in history.

Definition at line 201 of file COutputLogger.cpp.

◆ getLoggerName()

std::string COutputLogger::getLoggerName ( ) const
inherited

Return the name of the COutputLogger instance.

See also
setLoggerName

Definition at line 143 of file COutputLogger.cpp.

◆ getMinLoggingLevel()

VerbosityLevel mrpt::system::COutputLogger::getMinLoggingLevel ( ) const
inlineinherited

◆ isLoggingLevelVisible()

bool mrpt::system::COutputLogger::isLoggingLevelVisible ( VerbosityLevel  level) const
inlineinherited

Definition at line 202 of file system/COutputLogger.h.

References mrpt::system::COutputLogger::m_min_verbosity_level.

Referenced by mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), and mrpt::system::COutputLoggerStreamWrapper::~COutputLoggerStreamWrapper().

Here is the caller graph for this function:

◆ logCond()

void COutputLogger::logCond ( const VerbosityLevel  level,
bool  cond,
const std::string &  msg_str 
) const
inherited

Log the given message only if the condition is satisfied.

See also
log, logFmt

Definition at line 131 of file COutputLogger.cpp.

◆ logDeregisterCallback()

bool COutputLogger::logDeregisterCallback ( output_logger_callback_t  userFunc)
inherited
Returns
true if an entry was found and deleted.

Definition at line 291 of file COutputLogger.cpp.

References getAddress(), and mrpt::system::COutputLogger::m_listCallbacks.

Here is the call graph for this function:

◆ logFmt()

void COutputLogger::logFmt ( const VerbosityLevel  level,
const char *  fmt,
  ... 
) const
inherited

◆ loggerReset()

void COutputLogger::loggerReset ( )
inherited

Reset the contents of the logger instance.

Called upon construction.

Definition at line 206 of file COutputLogger.cpp.

References mrpt::system::LVL_INFO.

◆ logging_levels_to_colors()

std::array< mrpt::system::TConsoleColor, NUMBER_OF_VERBOSITY_LEVELS > & COutputLogger::logging_levels_to_colors ( )
staticinherited

Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor.

Handy for coloring the input based on the verbosity of the message

Definition at line 47 of file COutputLogger.cpp.

References logging_levels_to_colors.

Referenced by mrpt::system::COutputLogger::TMsg::dumpToConsole().

Here is the caller graph for this function:

◆ logging_levels_to_names()

std::array< std::string, NUMBER_OF_VERBOSITY_LEVELS > & COutputLogger::logging_levels_to_names ( )
staticinherited

Map from VerbosityLevels to their corresponding names.

Handy for printing the current message VerbosityLevel along with the actual content

Definition at line 60 of file COutputLogger.cpp.

References logging_levels_to_names.

Referenced by mrpt::system::COutputLogger::TMsg::getAsString().

Here is the caller graph for this function:

◆ logRegisterCallback()

void COutputLogger::logRegisterCallback ( output_logger_callback_t  userFunc)
inherited

Definition at line 278 of file COutputLogger.cpp.

References mrpt::system::COutputLogger::m_listCallbacks.

◆ logStr()

void COutputLogger::logStr ( const VerbosityLevel  level,
std::string_view  msg_str 
) const
inherited

Main method to add the specified message string to the logger.

See also
logCond, logFmt

Definition at line 72 of file COutputLogger.cpp.

References mrpt::system::COutputLogger::TMsg::body, mrpt::system::COutputLogger::TMsg::dumpToConsole(), mrpt::system::COutputLogger::TMsg::level, mrpt::system::COutputLogger::TMsg::name, and mrpt::system::COutputLogger::TMsg::timestamp.

Referenced by mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), mrpt::system::COutputLoggerStreamWrapper::~COutputLoggerStreamWrapper(), and mrpt::system::CTimeLoggerSaveAtDtor::~CTimeLoggerSaveAtDtor().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setLoggerName()

void COutputLogger::setLoggerName ( const std::string &  name)
inherited

◆ setMinLoggingLevel()

void COutputLogger::setMinLoggingLevel ( const VerbosityLevel  level)
inherited

Set the minimum logging level for which the incoming logs are going to be taken into account.

String messages with specified VerbosityLevel smaller than the min, will not be outputted to the screen and neither will a record of them be stored in by the COutputLogger instance

Definition at line 144 of file COutputLogger.cpp.

Referenced by mrpt::maps::CRandomFieldGridMap2D::enableVerbose(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), generic_kf_slam_test(), generic_pf_test(), generic_rbpf_slam_test(), mrpt::apps::RawlogGrabberApp::initialize(), mrpt::hwdrivers::CHokuyoURG::initialize(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), and mrpt::apps::ICP_SLAM_App_Base::run().

Here is the caller graph for this function:

◆ setVerbosityLevel()

void COutputLogger::setVerbosityLevel ( const VerbosityLevel  level)
inherited

◆ writeLogToFile()

void COutputLogger::writeLogToFile ( const std::string *  fname_in = nullptr) const
inherited

Write the contents of the COutputLogger instance to an external file.

Upon call to this method, COutputLogger dumps the contents of all the logged commands so far to the specified external file. By default the filename is set to ${LOGGERNAME}.log except if the fname parameter is provided

See also
dumpToConsole, getAsString

Definition at line 165 of file COutputLogger.cpp.

References ASSERTMSG_, and mrpt::format().

Here is the call graph for this function:

Member Data Documentation

◆ logging_enable_console_output

bool mrpt::system::COutputLogger::logging_enable_console_output {true}
inherited

[Default=true] Set it to false in case you don't want the logged messages to be dumped to the output automatically.

Definition at line 240 of file system/COutputLogger.h.

◆ logging_enable_keep_record

bool mrpt::system::COutputLogger::logging_enable_keep_record {false}
inherited

[Default=false] Enables storing all messages into an internal list.

See also
writeLogToFile, getLogAsString

Definition at line 243 of file system/COutputLogger.h.

◆ m_grid_feat_extr

COccupancyGridMapFeatureExtractor mrpt::slam::CGridMapAligner::m_grid_feat_extr
private

Grid map features extractor.

Definition at line 242 of file CGridMapAligner.h.

◆ m_min_verbosity_level

VerbosityLevel mrpt::system::COutputLogger::m_min_verbosity_level {LVL_INFO}
protectedinherited

Provided messages with VerbosityLevel smaller than this value shall be ignored.

Definition at line 253 of file system/COutputLogger.h.

Referenced by mrpt::system::COutputLogger::getMinLoggingLevel(), and mrpt::system::COutputLogger::isLoggingLevelVisible().

◆ options

mrpt::slam::CGridMapAligner::TConfigParams mrpt::slam::CGridMapAligner::options



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020