Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
ov_core::YamlParser Class Reference

Helper class to do OpenCV yaml parsing from both file and ROS. More...

#include <opencv_yaml_parse.h>

Public Member Functions

std::string get_config_folder ()
 Will get the folder this config file is in. More...
 
template<class T >
void parse_config (const std::string &node_name, T &node_result, bool required=true)
 Custom parser for the ESTIMATOR parameters. More...
 
void parse_external (const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name, Eigen::Matrix3d &node_result, bool required=true)
 Custom parser for Matrix3d in the external parameter files with levels. More...
 
void parse_external (const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name, Eigen::Matrix4d &node_result, bool required=true)
 Custom parser for Matrix4d in the external parameter files with levels. More...
 
template<class T >
void parse_external (const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name, T &node_result, bool required=true)
 Custom parser for the external parameter files with levels. More...
 
bool successful () const
 Check to see if all parameters were read succesfully. More...
 
 YamlParser (const std::string &config_path, bool fail_if_not_found=true)
 Constructor that loads all three configuration files. More...
 

Private Member Functions

void parse (const cv::FileNode &file_node, const std::string &node_name, bool &node_result, bool required=true)
 Custom parser for booleans (0,false,False,FALSE=>false and 1,true,True,TRUE=>false) More...
 
void parse (const cv::FileNode &file_node, const std::string &node_name, Eigen::Matrix3d &node_result, bool required=true)
 Custom parser for camera extrinsic 3x3 transformations. More...
 
void parse (const cv::FileNode &file_node, const std::string &node_name, Eigen::Matrix4d &node_result, bool required=true)
 Custom parser for camera extrinsic 4x4 transformations. More...
 
template<class T >
void parse (const cv::FileNode &file_node, const std::string &node_name, T &node_result, bool required=true)
 This function will try to get the requested parameter from our config. More...
 
template<class T >
void parse_config_yaml (const std::string &node_name, T &node_result, bool required=true)
 Custom parser for the ESTIMATOR parameters. More...
 
template<class T >
void parse_external_yaml (const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name, T &node_result, bool required=true)
 Custom parser for the EXTERNAL parameter files with levels. More...
 

Static Private Member Functions

static bool node_found (const cv::FileNode &file_node, const std::string &node_name)
 Given a YAML node object, this check to see if we have a valid key. More...
 

Private Attributes

bool all_params_found_successfully = true
 Record if all parameters were found. More...
 
std::shared_ptr< cv::FileStorage > config
 Our config file with the data in it. More...
 
std::string config_path_
 Path to the config file. More...
 

Detailed Description

Helper class to do OpenCV yaml parsing from both file and ROS.

The logic is as follows:

NOTE: There are no "nested" yaml parameters. They are all under the "root" of the yaml file!!! This limits things quite a bit, but simplified the below implementation.

NOTE: The camera and imu have nested, but those are handled externally. They first read the "imu0" or "cam1" level, after-which all values are at the same level.

Definition at line 58 of file opencv_yaml_parse.h.

Constructor & Destructor Documentation

◆ YamlParser()

ov_core::YamlParser::YamlParser ( const std::string &  config_path,
bool  fail_if_not_found = true 
)
inlineexplicit

Constructor that loads all three configuration files.

Parameters
config_pathPath to the YAML file we will parse
fail_if_not_foundIf we should terminate the program if we can't open the config file

Definition at line 65 of file opencv_yaml_parse.h.

Member Function Documentation

◆ get_config_folder()

std::string ov_core::YamlParser::get_config_folder ( )
inline

Will get the folder this config file is in.

Returns
Config folder

Definition at line 103 of file opencv_yaml_parse.h.

◆ node_found()

static bool ov_core::YamlParser::node_found ( const cv::FileNode &  file_node,
const std::string &  node_name 
)
inlinestaticprivate

Given a YAML node object, this check to see if we have a valid key.

Parameters
file_nodeOpenCV file node we will get the data from
node_nameName of the node
Returns
True if we can get the data

Definition at line 336 of file opencv_yaml_parse.h.

◆ parse() [1/4]

void ov_core::YamlParser::parse ( const cv::FileNode &  file_node,
const std::string &  node_name,
bool &  node_result,
bool  required = true 
)
inlineprivate

Custom parser for booleans (0,false,False,FALSE=>false and 1,true,True,TRUE=>false)

Parameters
file_nodeOpenCV file node we will get the data from
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 392 of file opencv_yaml_parse.h.

◆ parse() [2/4]

void ov_core::YamlParser::parse ( const cv::FileNode &  file_node,
const std::string &  node_name,
Eigen::Matrix3d &  node_result,
bool  required = true 
)
inlineprivate

Custom parser for camera extrinsic 3x3 transformations.

Parameters
file_nodeOpenCV file node we will get the data from
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 448 of file opencv_yaml_parse.h.

◆ parse() [3/4]

void ov_core::YamlParser::parse ( const cv::FileNode &  file_node,
const std::string &  node_name,
Eigen::Matrix4d &  node_result,
bool  required = true 
)
inlineprivate

Custom parser for camera extrinsic 4x4 transformations.

Parameters
file_nodeOpenCV file node we will get the data from
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 488 of file opencv_yaml_parse.h.

◆ parse() [4/4]

template<class T >
void ov_core::YamlParser::parse ( const cv::FileNode &  file_node,
const std::string &  node_name,
T &  node_result,
bool  required = true 
)
inlineprivate

This function will try to get the requested parameter from our config.

If it is unable to find it, it will give a warning to the user it couldn't be found.

Template Parameters
TType of parameter we are looking for.
Parameters
file_nodeOpenCV file node we will get the data from
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 357 of file opencv_yaml_parse.h.

◆ parse_config()

template<class T >
void ov_core::YamlParser::parse_config ( const std::string &  node_name,
T &  node_result,
bool  required = true 
)
inline

Custom parser for the ESTIMATOR parameters.

This will load the data from the main config file. If it is unable it will give a warning to the user it couldn't be found.

Template Parameters
TType of parameter we are looking for.
Parameters
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 122 of file opencv_yaml_parse.h.

◆ parse_config_yaml()

template<class T >
void ov_core::YamlParser::parse_config_yaml ( const std::string &  node_name,
T &  node_result,
bool  required = true 
)
inlineprivate

Custom parser for the ESTIMATOR parameters.

This will load the data from the main config file. If it is unable it will give a warning to the user it couldn't be found.

Template Parameters
TType of parameter we are looking for.
Parameters
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 548 of file opencv_yaml_parse.h.

◆ parse_external() [1/3]

void ov_core::YamlParser::parse_external ( const std::string &  external_node_name,
const std::string &  sensor_name,
const std::string &  node_name,
Eigen::Matrix3d &  node_result,
bool  required = true 
)
inline

Custom parser for Matrix3d in the external parameter files with levels.

This will first load the external file requested. From there it will try to find the first level requested (e.g. imu0, cam0, cam1). Then the requested node can be found under this sensor name. ROS can override the config with <sensor_name>_<node_name> (e.g., cam0_distortion).

Parameters
external_node_nameName of the node we will get our relative path from
sensor_nameThe first level node we will try to get the requested node under
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 195 of file opencv_yaml_parse.h.

◆ parse_external() [2/3]

void ov_core::YamlParser::parse_external ( const std::string &  external_node_name,
const std::string &  sensor_name,
const std::string &  node_name,
Eigen::Matrix4d &  node_result,
bool  required = true 
)
inline

Custom parser for Matrix4d in the external parameter files with levels.

This will first load the external file requested. From there it will try to find the first level requested (e.g. imu0, cam0, cam1). Then the requested node can be found under this sensor name. ROS can override the config with <sensor_name>_<node_name> (e.g., cam0_distortion).

Parameters
external_node_nameName of the node we will get our relative path from
sensor_nameThe first level node we will try to get the requested node under
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 242 of file opencv_yaml_parse.h.

◆ parse_external() [3/3]

template<class T >
void ov_core::YamlParser::parse_external ( const std::string &  external_node_name,
const std::string &  sensor_name,
const std::string &  node_name,
T &  node_result,
bool  required = true 
)
inline

Custom parser for the external parameter files with levels.

This will first load the external file requested. From there it will try to find the first level requested (e.g. imu0, cam0, cam1). Then the requested node can be found under this sensor name. ROS can override the config with <sensor_name>_<node_name> (e.g., cam0_distortion).

Template Parameters
TType of parameter we are looking for.
Parameters
external_node_nameName of the node we will get our relative path from
sensor_nameThe first level node we will try to get the requested node under
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 158 of file opencv_yaml_parse.h.

◆ parse_external_yaml()

template<class T >
void ov_core::YamlParser::parse_external_yaml ( const std::string &  external_node_name,
const std::string &  sensor_name,
const std::string &  node_name,
T &  node_result,
bool  required = true 
)
inlineprivate

Custom parser for the EXTERNAL parameter files with levels.

This will first load the external file requested. From there it will try to find the first level requested (e.g. imu0, cam0, cam1). Then the requested node can be found under this sensor name. ROS can override the config with <sensor_name>_<node_name> (e.g., cam0_distortion).

Template Parameters
TType of parameter we are looking for.
Parameters
external_node_nameName of the node we will get our relative path from
sensor_nameThe first level node we will try to get the requested node under
node_nameName of the node
node_resultResulting value (should already have default value in it)
requiredIf this parameter is required by the user to set

Definition at line 580 of file opencv_yaml_parse.h.

◆ successful()

bool ov_core::YamlParser::successful ( ) const
inline

Check to see if all parameters were read succesfully.

Returns
True if we found all parameters

Definition at line 109 of file opencv_yaml_parse.h.

Member Data Documentation

◆ all_params_found_successfully

bool ov_core::YamlParser::all_params_found_successfully = true
private

Record if all parameters were found.

Definition at line 318 of file opencv_yaml_parse.h.

◆ config

std::shared_ptr<cv::FileStorage> ov_core::YamlParser::config
private

Our config file with the data in it.

Definition at line 315 of file opencv_yaml_parse.h.

◆ config_path_

std::string ov_core::YamlParser::config_path_
private

Path to the config file.

Definition at line 312 of file opencv_yaml_parse.h.


The documentation for this class was generated from the following file:


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17