MRPT  1.9.9
mrpt::slam::CICP Class Reference

Detailed Description

Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a point map wrt a grid map.

CICP::AlignPDF() or CICP::Align() are the two main entry points of the algorithm.

To choose among existing ICP algorithms or customizing their parameters, see CICP::TConfigParams and the member options.

There exists an extension of the original ICP algorithm that provides multihypotheses-support for the correspondences, and which generates a Sum-of-Gaussians (SOG) PDF as output. See mrpt::tfest::se2_l2_robust()

For further details on the implemented methods, check the web: https://www.mrpt.org/Iterative_Closest_Point_(ICP)_and_other_matching_algorithms

For a paper explaining some of the basic equations, see for example: J. Martinez, J. Gonzalez, J. Morales, A. Mandow, A. Garcia-Cerezo, "Mobile robot motion estimation by 2D scan matching with genetic and iterative closest point algorithms", Journal of Field Robotics, vol. 23, no. 1, pp. 21-34, 2006. ( http://babel.isa.uma.es/~jlblanco/papers/martinez2006gil.pdf )

See also
CMetricMapsAlignmentAlgorithm

Definition at line 64 of file CICP.h.

#include <mrpt/slam/CICP.h>

Inheritance diagram for mrpt::slam::CICP:

Classes

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

Public Member Functions

 CICP ()
 Constructor with the default options. More...
 
 CICP (const TConfigParams &icpParams)
 Constructor that directly set the ICP params from a given struct. More...
 
 ~CICP () override=default
 Destructor. More...
 
mrpt::poses::CPosePDF::Ptr AlignPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, float *runningTime=nullptr, void *info=nullptr) override
 An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map. More...
 
mrpt::poses::CPose3DPDF::Ptr Align3DPDF (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, float *runningTime=nullptr, void *info=nullptr) override
 The virtual method for aligning a pair of metric maps, aligning the full 6D pose. More...
 
mrpt::poses::CPosePDF::Ptr Align (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose2D &grossEst, float *runningTime=nullptr, void *info=nullptr)
 The method for aligning a pair of metric maps, aligning only 2D + orientation. More...
 
mrpt::poses::CPose3DPDF::Ptr Align3D (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3D &grossEst, float *runningTime=nullptr, void *info=nullptr)
 The method for aligning a pair of metric maps, aligning the full 6D pose. More...
 

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

TConfigParams options
 The options employed by the ICP align. More...
 

Protected Member Functions

float kernel (const float &x2, const float &rho2)
 Computes:

\[ K(x^2) = \frac{x^2}{x^2+\rho^2} \]

or just return the input if options.useKernel = false. More...

 
mrpt::poses::CPosePDF::Ptr ICP_Method_Classic (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
 
mrpt::poses::CPosePDF::Ptr ICP_Method_LM (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
 
mrpt::poses::CPose3DPDF::Ptr ICP3D_Method_Classic (const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
 

Protected Attributes

VerbosityLevel m_min_verbosity_level {LVL_INFO}
 Provided messages with VerbosityLevel smaller than this value shall be ignored. 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, const std::string &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)
 

Constructor & Destructor Documentation

◆ CICP() [1/2]

mrpt::slam::CICP::CICP ( )
inline

Constructor with the default options.

Definition at line 183 of file CICP.h.

◆ CICP() [2/2]

mrpt::slam::CICP::CICP ( const TConfigParams icpParams)
inline

Constructor that directly set the ICP params from a given struct.

See also
options

Definition at line 186 of file CICP.h.

◆ ~CICP()

mrpt::slam::CICP::~CICP ( )
overridedefault

Destructor.

Member Function Documentation

◆ Align()

CPosePDF::Ptr CMetricMapsAlignmentAlgorithm::Align ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose2D grossEst,
float *  runningTime = nullptr,
void info = nullptr 
)
inherited

The method for aligning a pair of metric maps, aligning only 2D + orientation.

The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into 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

Definition at line 25 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(), and mrpt::slam::CMetricMapBuilderICP::processObservation().

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,
float *  runningTime = nullptr,
void info = nullptr 
)
inherited

The method for aligning a pair of metric maps, aligning the full 6D pose.

The meaning of some parameters and the kind of the maps to be aligned are implementation dependant, so look into 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 CPose3D(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

Definition at line 36 of file CMetricMapsAlignmentAlgorithm.cpp.

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

Referenced by TEST_F().

Here is the caller graph for this function:

◆ Align3DPDF()

CPose3DPDF::Ptr CICP::Align3DPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPose3DPDFGaussian initialEstimationPDF,
float *  runningTime = nullptr,
void info = nullptr 
)
overridevirtual

The virtual method for aligning a pair of metric maps, aligning the full 6D pose.

The meaning of some parameters are implementation dependant, so look at the derived classes for more details. The goal is to find a PDF for the pose displacement between maps, that is, 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 a "options" structure in the implementation classes.
Parameters
m1[IN] The first map (MUST BE A COccupancyGridMap2D derived class)
m2[IN] The second map. (MUST BE A CPointsMap derived class) The pose of this map respect to m1 is to be estimated.
initialEstimationPDF[IN] An initial gross estimation for the displacement.
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

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

Definition at line 914 of file CICP.cpp.

References mrpt::slam::icpClassic, mrpt::slam::icpLevenbergMarquardt, MRPT_END, MRPT_START, MRPT_TODO, THROW_EXCEPTION, and THROW_EXCEPTION_FMT.

◆ AlignPDF()

CPosePDF::Ptr CICP::AlignPDF ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
float *  runningTime = nullptr,
void info = nullptr 
)
overridevirtual

An implementation of CMetricMapsAlignmentAlgorithm for the case of a point maps and a occupancy grid/point map.

This method computes the PDF of the displacement (relative pose) between two maps: the relative pose of m2 with respect to m1. This pose is returned as a PDF rather than a single value.

Note
This method can be configurated with "CICP::options"
The output PDF is a CPosePDFGaussian if "doRANSAC=false", or a CPosePDFSOG otherwise.
Parameters
m1[IN] The first map (CAN BE A mrpt::poses::CPointsMap derived class or a mrpt::slam::COccupancyGrid2D class)
m2[IN] The second map. (MUST BE A mrpt::poses::CPointsMap derived class)The pose of this map respect to m1 is to be estimated.
initialEstimationPDF[IN] An initial gross estimation for the displacement.
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] A pointer to a CICP::TReturnInfo, or nullptr if it isn't needed.
Returns
A smart pointer to the output estimated pose PDF.
See also
CMetricMapsAlignmentAlgorithm, CICP::options, CICP::TReturnInfo

Implements mrpt::slam::CMetricMapsAlignmentAlgorithm.

Definition at line 36 of file CICP.cpp.

References mrpt::slam::icpClassic, mrpt::slam::icpLevenbergMarquardt, MRPT_END, MRPT_START, and THROW_EXCEPTION_FMT.

◆ 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
See also
setMinLoggingLevel

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

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

Referenced by mrpt::maps::CRandomFieldGridMap2D::isEnabledVerbose(), and mrpt::slam::CMetricMapBuilderRBPF::processActionObservation().

Here is the caller graph for this function:

◆ ICP3D_Method_Classic()

◆ ICP_Method_Classic()

CPosePDF::Ptr CICP::ICP_Method_Classic ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
TReturnInfo outInfo 
)
protected

Definition at line 181 of file CICP.cpp.

References mrpt::maps::TMatchingParams::angularDistPivotPoint, ASSERT_, mrpt::maps::TMatchingExtraResults::correspondencesRatio, mrpt::maps::TMatchingParams::decimation_other_map_points, mrpt::maps::CMetricMap::determineMatching2D(), mrpt::slam::CICP::TReturnInfo::goodness, mrpt::slam::icpCovFiniteDifferences, mrpt::slam::icpCovLinealMSE, mrpt::math::MatrixBase< Scalar, Derived >::inverse_LLt(), mrpt::maps::CMetricMap::isEmpty(), mrpt::math::MatrixBase< Scalar, Derived >::matProductOf_AAt(), mrpt::maps::TMatchingParams::maxAngularDistForCorrespondence, mrpt::maps::TMatchingParams::maxDistForCorrespondence, mrpt::poses::CPosePDFGaussian::mean, MRPT_END, MRPT_START, mrpt::slam::CICP::TReturnInfo::nIterations, mrpt::maps::TMatchingParams::offset_other_map_points, mrpt::maps::TMatchingParams::onlyKeepTheClosest, mrpt::maps::TMatchingParams::onlyUniqueRobust, mrpt::math::TPose2D::phi, mrpt::poses::CPose2D::phi(), mrpt::slam::CICP::TReturnInfo::quality, results, mrpt::tfest::se2_l2(), mrpt::tfest::se2_l2_robust(), mrpt::square(), THROW_EXCEPTION_FMT, mrpt::math::wrapToPi(), mrpt::math::TPose2D::x, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x_incr(), mrpt::math::TPose2D::y, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y_incr().

Here is the call graph for this function:

◆ ICP_Method_LM()

CPosePDF::Ptr CICP::ICP_Method_LM ( const mrpt::maps::CMetricMap m1,
const mrpt::maps::CMetricMap m2,
const mrpt::poses::CPosePDFGaussian initialEstimationPDF,
TReturnInfo outInfo 
)
protected

Definition at line 553 of file CICP.cpp.

References mrpt::maps::TMatchingParams::angularDistPivotPoint, mrpt::math::CMatrixFixed< T, ROWS, COLS >::asEigen(), mrpt::math::CMatrixDynamic< T >::asEigen(), ASSERT_, mrpt::math::CMatrixFixed< T, ROWS, COLS >::cast_double(), CLASS_ID, mrpt::math::closestSquareDistanceFromPointToLine(), mrpt::maps::TMatchingExtraResults::correspondencesRatio, mrpt::maps::TMatchingParams::decimation_other_map_points, mrpt::rtti::TRuntimeClassId::derivedFrom(), mrpt::maps::CMetricMap::GetRuntimeClass(), mrpt::slam::CICP::TReturnInfo::goodness, mrpt::math::MatrixBase< T, CMatrixFixed< T, ROWS, COLS > >::inverse_LLt(), mrpt::maps::CMetricMap::isEmpty(), mrpt::math::MatrixBase< Scalar, Derived >::matProductOf_AAt(), mrpt::maps::TMatchingParams::maxAngularDistForCorrespondence, mrpt::maps::TMatchingParams::maxDistForCorrespondence, mrpt::poses::CPosePDFGaussian::mean, MRPT_END, MRPT_START, mrpt::slam::CICP::TReturnInfo::nIterations, mrpt::maps::TMatchingParams::offset_other_map_points, mrpt::maps::TMatchingParams::onlyKeepTheClosest, mrpt::maps::TMatchingParams::onlyUniqueRobust, mrpt::comms::operator<<(), mrpt::system::pause(), mrpt::poses::CPose2D::phi(), mrpt::slam::CICP::TReturnInfo::quality, mrpt::math::CMatrixDynamic< T >::setSize(), mrpt::square(), mrpt::tfest::TMatchingPairList::squareErrorVector(), mrpt::math::sum(), mrpt::math::wrapToPi(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().

Here is the call graph for this function:

◆ isLoggingLevelVisible()

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

Definition at line 201 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:

◆ kernel()

float CICP::kernel ( const float &  x2,
const float &  rho2 
)
protected

Computes:

\[ K(x^2) = \frac{x^2}{x^2+\rho^2} \]

or just return the input if options.useKernel = false.

Definition at line 171 of file CICP.cpp.

◆ 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,
const std::string 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

Set the name of the COutputLogger instance.

See also
getLoggerName

Definition at line 138 of file COutputLogger.cpp.

Referenced by mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::slam::CMonteCarloLocalization2D::CMonteCarloLocalization2D(), mrpt::slam::CMonteCarloLocalization3D::CMonteCarloLocalization3D(), and mrpt::graphslam::CWindowManager::initCWindowManager().

Here is the caller graph for this function:

◆ 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(), mrpt::hwdrivers::CHokuyoURG::initialize(), and mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().

Here is the caller graph for this function:

◆ setVerbosityLevel()

void COutputLogger::setVerbosityLevel ( const VerbosityLevel  level)
inherited

alias of setMinLoggingLevel()

Definition at line 149 of file COutputLogger.cpp.

Referenced by mrpt::nav::CAbstractNavigator::CAbstractNavigator(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::comms::CServerTCPSocket::CServerTCPSocket(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), and mrpt::math::ransac_detect_2D_lines().

Here is the caller graph for this function:

◆ 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 239 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 242 of file system/COutputLogger.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 252 of file system/COutputLogger.h.

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

◆ options




Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019