class
YamlParserHelper class to do OpenCV yaml parsing from both file and ROS.
Contents
The logic is as follows:
- Given a path to the main config file we will load it into our cv::
FileStorage object. - From there the user can request for different parameters of different types from the config.
- If we have ROS, then we will also check to see if the user has overridden any config files via ROS.
- The ROS parameters always take priority over the ones in our config.
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.
Constructors, destructors, conversion operators
- YamlParser(const std::string& config_path, bool fail_if_not_found = true) explicit
- Constructor that loads all three configuration files.
Public functions
- auto get_config_folder() -> std::string
- Will get the folder this config file is in.
- auto successful() const -> bool
- Check to see if all parameters were read succesfully.
-
template<class T>void parse_config(const std::string& node_name, T& node_result, bool required = true)
- Custom parser for the ESTIMATOR parameters.
-
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.
- 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.
- 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.
Function documentation
ov_core:: YamlParser:: YamlParser(const std::string& config_path,
bool fail_if_not_found = true) explicit
Constructor that loads all three configuration files.
Parameters | |
---|---|
config_path | Path to the YAML file we will parse |
fail_if_not_found | If we should terminate the program if we can't open the config file |
std::string ov_core:: YamlParser:: get_config_folder()
Will get the folder this config file is in.
Returns | Config folder |
---|
bool ov_core:: YamlParser:: successful() const
Check to see if all parameters were read succesfully.
Returns | True if we found all parameters |
---|
template<class T>
void ov_core:: YamlParser:: parse_config(const std::string& node_name,
T& node_result,
bool required = true)
Custom parser for the ESTIMATOR parameters.
Template parameters | |
---|---|
T | Type of parameter we are looking for. |
Parameters | |
node_name | Name of the node |
node_result | Resulting value (should already have default value in it) |
required | If this parameter is required by the user to set |
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<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)
Custom parser for the external parameter files with levels.
Template parameters | |
---|---|
T | Type of parameter we are looking for. |
Parameters | |
external_node_name | Name of the node we will get our relative path from |
sensor_name | The first level node we will try to get the requested node under |
node_name | Name of the node |
node_result | Resulting value (should already have default value in it) |
required | If this parameter is required by the user to set |
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).
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)
Custom parser for Matrix3d in the external parameter files with levels.
Parameters | |
---|---|
external_node_name | Name of the node we will get our relative path from |
sensor_name | The first level node we will try to get the requested node under |
node_name | Name of the node |
node_result | Resulting value (should already have default value in it) |
required | If this parameter is required by the user to set |
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).
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)
Custom parser for Matrix4d in the external parameter files with levels.
Parameters | |
---|---|
external_node_name | Name of the node we will get our relative path from |
sensor_name | The first level node we will try to get the requested node under |
node_name | Name of the node |
node_result | Resulting value (should already have default value in it) |
required | If this parameter is required by the user to set |
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).