MRPT
2.0.1
|
This class allows loading and storing values and vectors of different types from ".ini" files easily.
The contents of the file will be modified by "write" operations in memory, and will be saved back to the file at the destructor, and only if at least one write operation has been applied.
Use base class CConfigFileBase
's methods read_{int,float,double,string,...}()
and write()
to actually read and write values.
See: Configuration file format in MRPT
Definition at line 31 of file config/CConfigFile.h.
#include <mrpt/config/CConfigFile.h>
Classes | |
struct | Impl |
Public Member Functions | |
CConfigFile (const std::string &fileName) | |
Constructor that opens a configuration file. More... | |
CConfigFile () | |
Constructor, does not open any file. More... | |
void | setFileName (const std::string &fil_path) |
Associate this object with the given file, so future read/write operations will be applied to that file (it's synchronized at destruction) More... | |
void | writeNow () |
Dumps the changes to the physical configuration file now, not waiting until destruction. More... | |
void | discardSavingChanges () |
Discard saving (current) changes to physical file upon destruction. More... | |
std::string | getAssociatedFile () const |
Returns the file currently open by this object. More... | |
~CConfigFile () override | |
Destructor. More... | |
void | getAllSections (std::vector< std::string > §ions) const override |
Returns a list with all the section names. More... | |
void | clear () override |
Empties the "config file". More... | |
void | getAllKeys (const std::string §ion, std::vector< std::string > &keys) const override |
Returs a list with all the keys into a section. More... | |
bool | sectionExists (const std::string §ion_name) const |
Checks if a given section exists (name is case insensitive) More... | |
bool | keyExists (const std::string §ion, 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 §ion, 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 §ion, 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 §ion, 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 §ion, 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 §ion, 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 | |
double | read_double (const std::string §ion, const std::string &name, double defaultValue, bool failIfNotFound=false) const |
float | read_float (const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const |
bool | read_bool (const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const |
int | read_int (const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const |
uint64_t | read_uint64_t (const std::string §ion, const std::string &name, uint64_t defaultValue, bool failIfNotFound=false) const |
std::string | read_string (const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const |
std::string | read_string_first_word (const std::string §ion, 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 §ion, 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 §ion, 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 §ion, 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 §ion, const std::string &name, const std::string &str) override |
A virtual method to write a generic string. More... | |
std::string | readString (const std::string §ion, 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 §ion, 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 | |
std::string | m_file |
The name of the file. More... | |
mrpt::pimpl< Impl > | m_impl |
bool | m_modified |
If modified since load. More... | |
CConfigFile::CConfigFile | ( | const std::string & | fileName | ) |
Constructor that opens a configuration file.
Definition at line 29 of file CConfigFile.cpp.
References m_file, m_impl, m_modified, MRPT_END, and MRPT_START.
CConfigFile::CConfigFile | ( | ) |
Constructor, does not open any file.
You should call "setFileName" before reading or writting or otherwise nothing will be read and write operations will be eventually lost. However, it's perfectly right to use this object without an associated file, in which case it will behave as an "in-memory" file.
Definition at line 44 of file CConfigFile.cpp.
References m_file, m_modified, MRPT_END, and MRPT_START.
|
override |
Destructor.
Definition at line 84 of file CConfigFile.cpp.
References mrpt::exception_to_str(), and writeNow().
|
overridevirtual |
Empties the "config file".
Implements mrpt::config::CConfigFileBase.
Definition at line 175 of file CConfigFile.cpp.
References m_impl.
void CConfigFile::discardSavingChanges | ( | ) |
Discard saving (current) changes to physical file upon destruction.
Definition at line 82 of file CConfigFile.cpp.
References m_modified.
Referenced by run_rnav_test().
|
overridevirtual |
Returs a list with all the keys into a section.
Implements mrpt::config::CConfigFileBase.
Definition at line 162 of file CConfigFile.cpp.
|
overridevirtual |
Returns a list with all the section names.
Implements mrpt::config::CConfigFileBase.
Definition at line 147 of file CConfigFile.cpp.
|
inline |
Returns the file currently open by this object.
Definition at line 81 of file config/CConfigFile.h.
References m_file.
|
inherited |
Returns a text block representing the contents of the config file in YAML format.
Definition at line 277 of file CConfigFileBase.cpp.
References MRPT_END, MRPT_START, sect, THROW_EXCEPTION, and val.
|
inherited |
Checks if a given key exists inside a section (case insensitive)
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().
|
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().
|
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().
|
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:
In the config file:
Which can be loaded with:
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().
|
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::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::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().
|
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::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::loadConfig_sensorSpecific(), mrpt::hwdrivers::CNTRIPEmitter::loadConfig_sensorSpecific(), mrpt::hwdrivers::CImpinjRFID::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().
|
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
std::exception | If 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().
|
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::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::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::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::RBPF_SLAM_App_Base::run(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RawlogGrabberApp::SensorThread(), mrpt::apps::ICP_SLAM_App_Live::SensorThread(), TEST(), and mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel().
|
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().
|
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().
|
inlineinherited |
Reads a configuration parameter of type vector, stored in the file as a string: "[v1 v2 v3 ... ]", where spaces could also be commas.
std::exception | If 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().
|
overrideprotectedvirtual |
A virtual method to read a generic string.
std::exception | If the key name is not found and "failIfNotFound" is true. Otherwise the "defaultValue" is returned. |
Implements mrpt::config::CConfigFileBase.
Definition at line 113 of file CConfigFile.cpp.
References mrpt::format(), m_file, m_impl, MRPT_END, MRPT_START, and THROW_EXCEPTION.
|
inherited |
Checks if a given section exists (name is case insensitive)
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().
|
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.
Definition at line 225 of file CConfigFileBase.cpp.
References mrpt::containers::clear(), MRPT_END, MRPT_START, sect, THROW_EXCEPTION, and val.
void CConfigFile::setFileName | ( | const std::string & | fil_path | ) |
Associate this object with the given file, so future read/write operations will be applied to that file (it's synchronized at destruction)
Definition at line 57 of file CConfigFile.cpp.
References m_file, m_impl, m_modified, MRPT_END, and MRPT_START.
|
inlineinherited |
Definition at line 107 of file config/CConfigFileBase.h.
Referenced by generic_kf_slam_test(), generic_pf_test(), generic_rbpf_slam_test(), run_rnav_test(), mrpt::nav::TWaypointSequence::save(), mrpt::nav::CPTG_DiffDrive_CC::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CCS::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CS::saveToConfigFile(), mrpt::nav::CPTG_Holo_Blend::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_alpha::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_C::saveToConfigFile(), mrpt::slam::CIncrementalMapPartitioner::TOptions::saveToConfigFile(), mrpt::img::TCamera::saveToConfigFile(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase::saveToConfigFile(), mrpt::nav::CHolonomicND::TOptions::saveToConfigFile(), mrpt::nav::CHolonomicFullEval::TOptions::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::saveToConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::nav::CPTG_RobotShape_Polygonal::saveToConfigFile(), mrpt::vision::TMultiResDescMatchOptions::saveToConfigFile(), mrpt::nav::CPTG_RobotShape_Circular::saveToConfigFile(), mrpt::vision::TMultiResDescOptions::saveToConfigFile(), TEST(), and mrpt::gui::CPanelCameraSelection::writeConfigFromVideoSourcePanel().
|
inlineinherited |
Definition at line 124 of file config/CConfigFileBase.h.
References mrpt::to_string(), and mrpt::config::CConfigFileBase::writeString().
|
inlineinherited |
Definition at line 135 of file config/CConfigFileBase.h.
References mrpt::to_string(), and mrpt::config::CConfigFileBase::writeString().
|
inherited |
Definition at line 38 of file CConfigFileBase.cpp.
References mrpt::format().
|
inherited |
Definition at line 52 of file CConfigFileBase.cpp.
References mrpt::format().
void CConfigFile::writeNow | ( | ) |
Dumps the changes to the physical configuration file now, not waiting until destruction.
Definition at line 71 of file CConfigFile.cpp.
References m_file, m_impl, m_modified, MRPT_END, and MRPT_START.
Referenced by ~CConfigFile().
|
overrideprotectedvirtual |
A virtual method to write a generic string.
Implements mrpt::config::CConfigFileBase.
Definition at line 96 of file CConfigFile.cpp.
References m_impl, m_modified, MRPT_END, MRPT_START, and THROW_EXCEPTION.
|
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().
|
private |
The name of the file.
Definition at line 35 of file config/CConfigFile.h.
Referenced by CConfigFile(), getAssociatedFile(), readString(), setFileName(), and writeNow().
|
private |
Definition at line 37 of file config/CConfigFile.h.
Referenced by CConfigFile(), clear(), getAllKeys(), getAllSections(), readString(), setFileName(), writeNow(), and writeString().
|
private |
If modified since load.
Definition at line 40 of file config/CConfigFile.h.
Referenced by CConfigFile(), discardSavingChanges(), setFileName(), writeNow(), and writeString().
Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020 |