|
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...
|
|
|
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...
|
|
Helper class to do OpenCV yaml parsing from both file and ROS.
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.
Definition at line 58 of file opencv_yaml_parse.h.
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_node | OpenCV file node we will get the data from |
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 |
Definition at line 392 of file opencv_yaml_parse.h.
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_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 |
Definition at line 195 of file opencv_yaml_parse.h.
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_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 |
Definition at line 242 of file opencv_yaml_parse.h.
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
-
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 |
Definition at line 158 of file opencv_yaml_parse.h.
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
-
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 |
Definition at line 580 of file opencv_yaml_parse.h.