MRPT  2.0.2
List of all members | Classes | Public Member Functions | Protected Member Functions | Private Attributes
mrpt::config::CConfigFileMemory Class Reference

Detailed Description

This class implements a config file-like interface over a memory-stored string list.

Use base class CConfigFileBase's methods read_{int,float,double,string,...}() and write() to actually read and write values.

It can also parse a YAML text block and expose its fields (up to the first level of hierarchy, as allowed by INI-like files). This can be used to port MRPT classes relying on INI files to using YAML files transparently. This feature required building MRPT with yaml-cpp, and is provided by CConfigFileMemory::setContentFromYAML().

See: Configuration file format in MRPT

Note
YAML support was introduced in MRPT 1.9.9

Definition at line 36 of file config/CConfigFileMemory.h.

#include <mrpt/config/CConfigFileMemory.h>

Inheritance diagram for mrpt::config::CConfigFileMemory:

Classes

struct  Impl
 

Public Member Functions

 CConfigFileMemory ()
 Empty constructor. More...
 
 CConfigFileMemory (const std::vector< std::string > &stringList)
 Constructor and initialize from a list of strings. More...
 
 CConfigFileMemory (const std::string &str)
 Constructor and initialize from string with the whole "config file". More...
 
 ~CConfigFileMemory () override
 dtor More...
 
void setContent (const std::vector< std::string > &stringList)
 Changes the contents of the virtual "config file". More...
 
void setContent (const std::string &str)
 Changes the contents of the virtual "config file". More...
 
void getContent (std::string &str) const
 Return the current contents of the virtual "config file". More...
 
std::string getContent () const
 
void clear () override
 Empties the virtual "config file". More...
 
void getAllSections (std::vector< std::string > &sections) const override
 Returns a list with all the section names. More...
 
void getAllKeys (const std::string &section, std::vector< std::string > &keys) const override
 Returs a list with all the keys into a section. More...
 
bool sectionExists (const std::string &section_name) const
 Checks if a given section exists (name is case insensitive) More...
 
bool keyExists (const std::string &section, const std::string &key) const
 Checks if a given key exists inside a section (case insensitive) More...
 
void setContentFromYAML (const std::string &yaml_block)
 Changes the contents of the virtual "config file" from a text block containing a YAML configuration text. More...
 
std::string getContentAsYAML () const
 Returns a text block representing the contents of the config file in YAML format. More...
 
template<typename enum_t , typename = std::enable_if_t<std::is_enum<enum_t>::value>>
void write (const std::string &section, const std::string &name, enum_t value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
 
Save a configuration parameter. Optionally pads with spaces up to

the desired width in number of characters (-1: no fill), and add a final comment field at the end of the line (a "// " prefix is automatically inserted).

template<typename data_t , typename = std::enable_if_t<!std::is_enum<data_t>::value>>
void write (const std::string &section, const std::string &name, const data_t &value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
 
template<typename data_t >
void write (const std::string &section, const std::string &name, const std::vector< data_t > &value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
 
void write (const std::string &section, const std::string &name, double value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
 
void write (const std::string &section, const std::string &name, float value, const int name_padding_width=-1, const int value_padding_width=-1, const std::string &comment=std::string())
 
Read a configuration parameter, launching exception if key name is

not found and failIfNotFound=true

double read_double (const std::string &section, const std::string &name, double defaultValue, bool failIfNotFound=false) const
 
float read_float (const std::string &section, const std::string &name, float defaultValue, bool failIfNotFound=false) const
 
bool read_bool (const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
 
int read_int (const std::string &section, const std::string &name, int defaultValue, bool failIfNotFound=false) const
 
uint64_t read_uint64_t (const std::string &section, const std::string &name, uint64_t defaultValue, bool failIfNotFound=false) const
 
std::string read_string (const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
 
std::string read_string_first_word (const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
 Reads a configuration parameter of type "string", and keeps only the first word (this can be used to eliminate possible comments at the end of the line) More...
 
template<class VECTOR_TYPE >
void read_vector (const std::string &section, const std::string &name, const VECTOR_TYPE &defaultValue, VECTOR_TYPE &outValues, bool failIfNotFound=false) const
 Reads a configuration parameter of type vector, stored in the file as a string: "[v1 v2 v3 ... ]", where spaces could also be commas. More...
 
template<class MATRIX_TYPE >
void read_matrix (const std::string &section, const std::string &name, MATRIX_TYPE &outMatrix, const MATRIX_TYPE &defaultMatrix=MATRIX_TYPE(), bool failIfNotFound=false) const
 Reads a configuration parameter as a matrix written in a matlab-like format - for example: "[2 3 4 ; 7 8 9]". More...
 
template<typename ENUMTYPE >
ENUMTYPE read_enum (const std::string &section, const std::string &name, const ENUMTYPE &defaultValue, bool failIfNotFound=false) const
 Reads an "enum" value, where the value in the config file can be either a numerical value or the symbolic name, for example: In the code: More...
 

Protected Member Functions

void writeString (const std::string &section, const std::string &name, const std::string &str) override
 A virtual method to write a generic string. More...
 
std::string readString (const std::string &section, const std::string &name, const std::string &defaultStr, bool failIfNotFound=false) const override
 A virtual method to read a generic string. More...
 
void writeString (const std::string &section, const std::string &name, const std::string &str, const int name_padding_width, const int value_padding_width, const std::string &comment)
 Write a generic string with optional padding and a comment field ("// ...") at the end of the line. More...
 

Private Attributes

mrpt::pimpl< Implm_impl
 

Constructor & Destructor Documentation

◆ CConfigFileMemory() [1/3]

CConfigFileMemory::CConfigFileMemory ( )

Empty constructor.

Upon construction, call any of the "setContent" method

Definition at line 47 of file CConfigFileMemory.cpp.

◆ CConfigFileMemory() [2/3]

CConfigFileMemory::CConfigFileMemory ( const std::vector< std::string > &  stringList)

Constructor and initialize from a list of strings.

Definition at line 28 of file CConfigFileMemory.cpp.

References mrpt::system::stringListAsString(), and THE_INI.

Here is the call graph for this function:

◆ CConfigFileMemory() [3/3]

CConfigFileMemory::CConfigFileMemory ( const std::string &  str)

Constructor and initialize from string with the whole "config file".

Definition at line 37 of file CConfigFileMemory.cpp.

References THE_INI.

◆ ~CConfigFileMemory()

CConfigFileMemory::~CConfigFileMemory ( )
overridedefault

dtor

Member Function Documentation

◆ clear()

void CConfigFileMemory::clear ( )
overridevirtual

Empties the virtual "config file".

Implements mrpt::config::CConfigFileBase.

Definition at line 138 of file CConfigFileMemory.cpp.

References m_impl.

◆ getAllKeys()

void CConfigFileMemory::getAllKeys ( const std::string &  section,
std::vector< std::string > &  keys 
) const
overridevirtual

Returs a list with all the keys into a section.

Implements mrpt::config::CConfigFileBase.

Definition at line 125 of file CConfigFileMemory.cpp.

References m_impl, and names.

Referenced by TEST(), and mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel().

Here is the caller graph for this function:

◆ getAllSections()

void CConfigFileMemory::getAllSections ( std::vector< std::string > &  sections) const
overridevirtual

Returns a list with all the section names.

Implements mrpt::config::CConfigFileBase.

Definition at line 113 of file CConfigFileMemory.cpp.

References m_impl, and names.

Referenced by mrpt::apps::RawlogGrabberApp::run(), TEST(), and mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel().

Here is the caller graph for this function:

◆ getContent() [1/2]

void CConfigFileMemory::getContent ( std::string &  str) const

Return the current contents of the virtual "config file".

Definition at line 65 of file CConfigFileMemory.cpp.

References m_impl.

Referenced by mrpt::img::TStereoCamera::dumpAsText(), mrpt::img::TCamera::dumpAsText(), mrpt::config::CLoadableOptions::dumpToTextStream(), mrpt::obs::CObservation3DRangeScan::getDescriptionAsText(), mrpt::nav::CAbstractNavigator::loadConfigFile(), and mrpt::gui::WxSubsystem::CWXMainFrame::OnTimerProcessRequests().

Here is the caller graph for this function:

◆ getContent() [2/2]

std::string mrpt::config::CConfigFileMemory::getContent ( ) const
inline

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

Definition at line 56 of file config/CConfigFileMemory.h.

◆ getContentAsYAML()

std::string CConfigFileBase::getContentAsYAML ( ) const
inherited

Returns a text block representing the contents of the config file in YAML format.

See also
setContentFromYAML()

Definition at line 277 of file CConfigFileBase.cpp.

References MRPT_END, MRPT_START, sect, THROW_EXCEPTION, and val.

◆ keyExists()

bool CConfigFileBase::keyExists ( const std::string &  section,
const std::string &  key 
) const
inherited

Checks if a given key exists inside a section (case insensitive)

See also
sectionExists()

Definition at line 215 of file CConfigFileBase.cpp.

References mrpt::system::os::_strcmpi().

Referenced by mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), and TEST().

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

◆ read_bool()

bool CConfigFileBase::read_bool ( const std::string &  section,
const std::string &  name,
bool  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 155 of file CConfigFileBase.cpp.

References mrpt::system::lowerCase(), and trim().

Referenced by mrpt::detectors::CFaceDetection::init(), mrpt::nav::TWaypointSequence::load(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CNTRIPEmitter::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCANBusReader::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CAbstractNavigator::loadConfigFile(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::loadFromConfigFile(), mrpt::vision::TMultiResDescOptions::loadFromConfigFile(), mrpt::hwdrivers::TCaptureOptions_DUO3D::loadOptionsFrom(), mrpt::hwdrivers::TCaptureOptions_FlyCapture2::loadOptionsFrom(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::loadParams(), CGraphSlamHandler< GRAPH_T >::readConfigFname(), mrpt::gui::CPanelCameraSelection::readConfigIntoVideoSourcePanel(), mrpt::apps::RawlogGrabberApp::run(), and mrpt::apps::ICP_SLAM_App_Base::run().

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

◆ read_double()

double CConfigFileBase::read_double ( const std::string &  section,
const std::string &  name,
double  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 106 of file CConfigFileBase.cpp.

References mrpt::format().

Referenced by mrpt::detectors::CCascadeClassifierDetection::init(), mrpt::detectors::CFaceDetection::init(), mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::nav::TWaypointSequence::load(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::img::TCamera::loadFromConfigFile(), mrpt::nav::CHolonomicFullEval::TOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::loadFromConfigFile(), mrpt::vision::TMultiResDescOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::loadParams(), mrpt::nav::CPTG_RobotShape_Polygonal::loadShapeFromConfigFile(), mrpt::topography::path_from_rtk_gps(), and TEST().

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

◆ read_enum()

template<typename ENUMTYPE >
ENUMTYPE mrpt::config::CConfigFileBase::read_enum ( const std::string &  section,
const std::string &  name,
const ENUMTYPE &  defaultValue,
bool  failIfNotFound = false 
) const
inlineinherited

Reads an "enum" value, where the value in the config file can be either a numerical value or the symbolic name, for example: In the code:

enum my_type_t { type_foo=0, type_bar };

In the config file:

[section]
type = type_bar // Use the symbolic name, or
type = 1 // use the numerical value (both lines will be
equivalent)

Which can be loaded with:

cfgfile.read_enum<my_type_t>("section","type", type_foo );
Note
For an enum type to work with this template it is required that it defines a specialization of mrpt::typemeta::TEnumType

Definition at line 269 of file config/CConfigFileBase.h.

References MRPT_END, MRPT_START, mrpt::typemeta::TEnumType< ENUMTYPE >::name2value(), mrpt::config::CConfigFileBase::read_string_first_word(), and THROW_EXCEPTION_FMT.

Referenced by mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::maps::CColouredPointsMap::TColourOptions::loadFromConfigFile(), mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::maps::CHeightGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::apps::ICP_SLAM_App_Base::run(), and mrpt::apps::RBPF_SLAM_App_Base::run().

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

◆ read_float()

float CConfigFileBase::read_float ( const std::string &  section,
const std::string &  name,
float  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 118 of file CConfigFileBase.cpp.

References mrpt::format().

Referenced by mrpt::hwdrivers::CWirelessPower::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGillAnemometer::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRaePID::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIbeoLuxETH::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSICKTim561Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::maps::CLandmarksMap::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::hwdrivers::TCaptureOptions_DUO3D::loadOptionsFrom(), and mrpt::hwdrivers::TCaptureOptions_FlyCapture2::loadOptionsFrom().

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

◆ read_int()

int CConfigFileBase::read_int ( const std::string &  section,
const std::string &  name,
int  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 130 of file CConfigFileBase.cpp.

References mrpt::format().

Referenced by mrpt::apps::ICP_SLAM_App_Rawlog::impl_initialize(), mrpt::apps::RBPF_SLAM_App_Rawlog::impl_initialize(), mrpt::detectors::CCascadeClassifierDetection::init(), mrpt::detectors::CFaceDetection::init(), mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::nav::TWaypointSequence::load(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CGillAnemometer::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRaePID::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboticHeadInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNTRIPEmitter::loadConfig_sensorSpecific(), mrpt::hwdrivers::CImpinjRFID::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSICKTim561Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCANBusReader::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile(), mrpt::graphslam::TSlidingWindow::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::loadFromConfigFile(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams::loadFromConfigFile(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::loadFromConfigFile(), mrpt::vision::TMultiResDescOptions::loadFromConfigFile(), mrpt::maps::CLandmarksMap::TMapDefinition::loadFromConfigFile_map_specific(), mrpt::hwdrivers::TCaptureOptions_DUO3D::loadOptionsFrom(), mrpt::hwdrivers::TCaptureOptions_FlyCapture2::loadOptionsFrom(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::loadParams(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::loadParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::loadParams(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::loadParams(), mrpt::gui::CPanelCameraSelection::readConfigIntoVideoSourcePanel(), mrpt::apps::ICP_SLAM_App_Base::run(), and TEST().

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

◆ read_matrix()

template<class MATRIX_TYPE >
void mrpt::config::CConfigFileBase::read_matrix ( const std::string &  section,
const std::string &  name,
MATRIX_TYPE &  outMatrix,
const MATRIX_TYPE &  defaultMatrix = MATRIX_TYPE(),
bool  failIfNotFound = false 
) const
inlineinherited

Reads a configuration parameter as a matrix written in a matlab-like format - for example: "[2 3 4 ; 7 8 9]".

This template method can be instantiated for matrices of the types: int, long, unsinged int, unsigned long, float, double, long double

Exceptions
std::exceptionIf the key name is not found and "failIfNotFound" is true. Otherwise the "defaultValue" is returned.

Definition at line 230 of file config/CConfigFileBase.h.

References mrpt::config::CConfigFileBase::readString(), and THROW_EXCEPTION_FMT.

Referenced by mrpt::topography::path_from_rtk_gps().

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

◆ read_string()

std::string CConfigFileBase::read_string ( const std::string &  section,
const std::string &  name,
const std::string &  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 171 of file CConfigFileBase.cpp.

References mrpt::system::trim().

Referenced by mrpt::apps::ICP_SLAM_App_Rawlog::impl_initialize(), mrpt::apps::RBPF_SLAM_App_Rawlog::impl_initialize(), mrpt::detectors::CCascadeClassifierDetection::init(), mrpt::apps::KFSLAMApp::initialize(), mrpt::nav::PlannerTPS_VirtualBase::internal_loadConfig_PTG(), mrpt::nav::TWaypointSequence::load(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CWirelessPower::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGillAnemometer::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRaePID::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboticHeadInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNTRIPEmitter::loadConfig_sensorSpecific(), mrpt::hwdrivers::CImpinjRFID::loadConfig_sensorSpecific(), mrpt::hwdrivers::CEnoseModular::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardENoses::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSICKTim561Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCANBusReader::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNationalInstrumentsDAQ::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CNavigatorManualSequence::loadConfigFile(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile(), mrpt::img::TStereoCamera::loadFromConfigFile(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase::loadFromConfigFile(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hwdrivers::TCaptureOptions_DUO3D::loadOptionsFrom(), mrpt::hwdrivers::TCaptureOptions_FlyCapture2::loadOptionsFrom(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::loadParams(), CGraphSlamHandler< GRAPH_T >::readConfigFname(), mrpt::gui::CPanelCameraSelection::readConfigIntoVideoSourcePanel(), mrpt::apps::KFSLAMApp::run(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::apps::RawlogGrabberApp::SensorThread(), mrpt::apps::ICP_SLAM_App_Live::SensorThread(), TEST(), and mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel().

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

◆ read_string_first_word()

std::string CConfigFileBase::read_string_first_word ( const std::string &  section,
const std::string &  name,
const std::string &  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Reads a configuration parameter of type "string", and keeps only the first word (this can be used to eliminate possible comments at the end of the line)

Definition at line 182 of file CConfigFileBase.cpp.

References mrpt::format(), THROW_EXCEPTION, and mrpt::system::tokenize().

Referenced by mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), and mrpt::config::CConfigFileBase::read_enum().

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

◆ read_uint64_t()

uint64_t CConfigFileBase::read_uint64_t ( const std::string &  section,
const std::string &  name,
uint64_t  defaultValue,
bool  failIfNotFound = false 
) const
inherited

Definition at line 142 of file CConfigFileBase.cpp.

References mrpt::system::os::_strtoull(), and mrpt::format().

Referenced by mrpt::hwdrivers::CEnoseModular::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardENoses::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNationalInstrumentsDAQ::loadConfig_sensorSpecific(), mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile(), mrpt::vision::TMultiResDescOptions::loadFromConfigFile(), and mrpt::hwdrivers::TCaptureOptions_FlyCapture2::loadOptionsFrom().

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

◆ read_vector()

template<class VECTOR_TYPE >
void mrpt::config::CConfigFileBase::read_vector ( const std::string &  section,
const std::string &  name,
const VECTOR_TYPE &  defaultValue,
VECTOR_TYPE &  outValues,
bool  failIfNotFound = false 
) const
inlineinherited

Reads a configuration parameter of type vector, stored in the file as a string: "[v1 v2 v3 ... ]", where spaces could also be commas.

Exceptions
std::exceptionIf the key name is not found and "failIfNotFound" is true. Otherwise the "defaultValue" is returned.

Definition at line 194 of file config/CConfigFileBase.h.

References mrpt::config::CConfigFileBase::readString(), mrpt::system::tokenize(), and val.

Referenced by mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CRoboticHeadInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardENoses::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::nav::CReactiveNavigationSystem::loadConfigFile(), mrpt::nav::CReactiveNavigationSystem3D::loadConfigFile(), mrpt::img::TCamera::loadFromConfigFile(), mrpt::nav::CHolonomicND::TOptions::loadFromConfigFile(), mrpt::nav::CHolonomicFullEval::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), and mrpt::vision::TMultiResDescOptions::loadFromConfigFile().

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

◆ readString()

std::string CConfigFileMemory::readString ( const std::string &  section,
const std::string &  name,
const std::string &  defaultStr,
bool  failIfNotFound = false 
) const
overrideprotectedvirtual

A virtual method to read a generic string.

Implements mrpt::config::CConfigFileBase.

Definition at line 83 of file CConfigFileMemory.cpp.

References mrpt::format(), m_impl, MRPT_END, MRPT_START, and THROW_EXCEPTION.

Here is the call graph for this function:

◆ sectionExists()

bool CConfigFileBase::sectionExists ( const std::string &  section_name) const
inherited

Checks if a given section exists (name is case insensitive)

See also
keyExists()

Definition at line 205 of file CConfigFileBase.cpp.

References mrpt::system::os::_strcmpi(), and sect.

Referenced by mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::apps::CGridMapAlignerApp::run(), and TEST().

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

◆ setContent() [1/2]

void CConfigFileMemory::setContent ( const std::vector< std::string > &  stringList)

Changes the contents of the virtual "config file".

Definition at line 52 of file CConfigFileMemory.cpp.

References mrpt::system::stringListAsString(), and THE_INI.

Referenced by mrpt::obs::CRawlog::getCommentTextAsConfigFile(), mrpt::apps::KFSLAMApp::initialize(), mrpt::apps::RawlogGrabberApp::initialize(), mrpt::apps::MonteCarloLocalization_Base::initialize(), mrpt::apps::RBPF_SLAM_App_Base::initialize(), mrpt::apps::ICP_SLAM_App_Base::initialize(), and TEST().

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

◆ setContent() [2/2]

void CConfigFileMemory::setContent ( const std::string &  str)

Changes the contents of the virtual "config file".

Definition at line 60 of file CConfigFileMemory.cpp.

References THE_INI.

◆ setContentFromYAML()

void CConfigFileBase::setContentFromYAML ( const std::string &  yaml_block)
inherited

Changes the contents of the virtual "config file" from a text block containing a YAML configuration text.

Refer to unit test yaml2config_unittest.cpp for examples of use.

See also
getContentAsYAML()

Definition at line 225 of file CConfigFileBase.cpp.

References mrpt::containers::clear(), MRPT_END, MRPT_START, sect, THROW_EXCEPTION, and val.

Here is the call graph for this function:

◆ write() [1/5]

template<typename enum_t , typename = std::enable_if_t<std::is_enum<enum_t>::value>>
void mrpt::config::CConfigFileBase::write ( const std::string &  section,
const std::string &  name,
enum_t  value,
const int  name_padding_width = -1,
const int  value_padding_width = -1,
const std::string &  comment = std::string() 
)
inlineinherited

◆ write() [2/5]

template<typename data_t , typename = std::enable_if_t<!std::is_enum<data_t>::value>>
void mrpt::config::CConfigFileBase::write ( const std::string &  section,
const std::string &  name,
const data_t value,
const int  name_padding_width = -1,
const int  value_padding_width = -1,
const std::string &  comment = std::string() 
)
inlineinherited

Definition at line 124 of file config/CConfigFileBase.h.

References mrpt::to_string(), and mrpt::config::CConfigFileBase::writeString().

Here is the call graph for this function:

◆ write() [3/5]

template<typename data_t >
void mrpt::config::CConfigFileBase::write ( const std::string &  section,
const std::string &  name,
const std::vector< data_t > &  value,
const int  name_padding_width = -1,
const int  value_padding_width = -1,
const std::string &  comment = std::string() 
)
inlineinherited

Definition at line 135 of file config/CConfigFileBase.h.

References mrpt::to_string(), and mrpt::config::CConfigFileBase::writeString().

Here is the call graph for this function:

◆ write() [4/5]

void CConfigFileBase::write ( const std::string &  section,
const std::string &  name,
double  value,
const int  name_padding_width = -1,
const int  value_padding_width = -1,
const std::string &  comment = std::string() 
)
inherited

Definition at line 38 of file CConfigFileBase.cpp.

References mrpt::format().

Here is the call graph for this function:

◆ write() [5/5]

void CConfigFileBase::write ( const std::string &  section,
const std::string &  name,
float  value,
const int  name_padding_width = -1,
const int  value_padding_width = -1,
const std::string &  comment = std::string() 
)
inherited

Definition at line 52 of file CConfigFileBase.cpp.

References mrpt::format().

Here is the call graph for this function:

◆ writeString() [1/2]

void CConfigFileBase::writeString ( const std::string &  section,
const std::string &  name,
const std::string &  str,
const int  name_padding_width,
const int  value_padding_width,
const std::string &  comment 
)
protectedinherited

Write a generic string with optional padding and a comment field ("// ...") at the end of the line.

Definition at line 70 of file CConfigFileBase.cpp.

References mrpt::format().

Here is the call graph for this function:

◆ writeString() [2/2]

void CConfigFileMemory::writeString ( const std::string &  section,
const std::string &  name,
const std::string &  str 
)
overrideprotectedvirtual

A virtual method to write a generic string.

Implements mrpt::config::CConfigFileBase.

Definition at line 71 of file CConfigFileMemory.cpp.

References MRPT_END, MRPT_START, THE_INI, and THROW_EXCEPTION.

Member Data Documentation

◆ m_impl

mrpt::pimpl<Impl> mrpt::config::CConfigFileMemory::m_impl
private

Definition at line 74 of file config/CConfigFileMemory.h.

Referenced by clear(), getAllKeys(), getAllSections(), getContent(), and readString().




Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020