Skip to content

Commit 2559f75

Browse files
authoredNov 1, 2017
Refactor ConfigParser (#236)
Refactor ConfigParser. The primary motivation is to allow defining parsing functions in other modules, so wave_utils does not depend on OpenCV, or any future classes we want to parse. Basically this is a wrapper around yaml-cpp's `convert` mechanism. However, by request I kept the interface to ConfigParser the same, so other classes still use `addParam`, `load(file)`, etc. Note that despite the templates, the parsing functions for Matrix, etc. are still compiled into the library. Only the same matrix types are still supported. - Remove huge enum and switch statements of types - Use templated Param class - Define enum for return codes instead of int
1 parent 814ca70 commit 2559f75

File tree

14 files changed

+306
-648
lines changed

14 files changed

+306
-648
lines changed
 

‎docs/examples/example_config_parser.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ int main() {
2222
// Note: We support the dot notation for yaml keys
2323

2424
// load the config file and assign values to variables
25-
if (parser.load("example_params.yaml") != 0) {
25+
if (parser.load("example_params.yaml") != wave::ConfigStatus::OK) {
2626
return -1;
2727
}
28-
}
28+
}

‎wave_matching/src/gicp.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ GICPMatcherParams::GICPMatcherParams(const std::string &config_path) {
1010
parser.addParam("r_eps", &this->r_eps);
1111
parser.addParam("fit_eps", &this->fit_eps);
1212

13-
if (parser.load(config_path) != 0) {
13+
if (parser.load(config_path) != ConfigStatus::OK) {
1414
ConfigException config_exception;
1515
throw config_exception;
1616
}

‎wave_matching/src/icp.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ ICPMatcherParams::ICPMatcherParams(const std::string &config_path) {
1616
this->covar_estimator =
1717
static_cast<ICPMatcherParams::covar_method>(covar_est_temp);
1818

19-
if (parser.load(config_path) != 0) {
19+
if (parser.load(config_path) != ConfigStatus::OK) {
2020
ConfigException config_exception;
2121
throw config_exception;
2222
}

‎wave_matching/src/ndt.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ NDTMatcherParams::NDTMatcherParams(const std::string &config_path) {
1010
parser.addParam("t_eps", &this->t_eps);
1111
parser.addParam("res", &this->res);
1212

13-
if (parser.load(config_path) != 0) {
13+
if (parser.load(config_path) != ConfigStatus::OK) {
1414
ConfigException config_exception;
1515
throw config_exception;
1616
}

‎wave_utils/include/wave/utils/config.hpp

+154-124
Original file line numberDiff line numberDiff line change
@@ -25,57 +25,54 @@ namespace wave {
2525
/** @addtogroup utils
2626
* @{ */
2727

28-
/**
29-
* An enum used by `ConfigParam` to denote the yaml value type.
30-
*
31-
* Currently we support parsing of the following data types:
32-
* - **Primitives**: `bool`, `int`, `float`, `double`, `std::string`
33-
* - **Arrays**: `std::vector<bool>`, `std::vector<int>`, `std::vector<float>`,
34-
* `std::vector<double>`, `std::vector<std::string>`
35-
* - **Vectors**: `Eigen::Vector2d`, `Eigen::Vector3d`, `Eigen::Vector4d`,
36-
* `Eigen::VectorXd`
37-
* - **Matrices**: `Eigen::Matrix2d`, `Eigen::Matrix3d`, `Eigen::Matrix4d`,
38-
* `Eigen::MatrixXd`
39-
*/
40-
enum ConfigDataType {
41-
TYPE_NOT_SET = 0,
42-
// PRIMITIVES
43-
BOOL = 1,
44-
INT = 2,
45-
FLOAT = 3,
46-
DOUBLE = 4,
47-
STRING = 5,
48-
// ARRAY
49-
BOOL_ARRAY = 11,
50-
INT_ARRAY = 12,
51-
FLOAT_ARRAY = 13,
52-
DOUBLE_ARRAY = 14,
53-
STRING_ARRAY = 15,
54-
// VECTOR
55-
VEC2 = 21,
56-
VEC3 = 22,
57-
VEC4 = 23,
58-
VECX = 24,
59-
// MATRIX
60-
MAT2 = 31,
61-
MAT3 = 32,
62-
MAT4 = 33,
63-
MATX = 34,
64-
CVMAT = 35
28+
/** Return codes for ConfigParser methods */
29+
enum class ConfigStatus {
30+
OK = 0, ///< Success
31+
MissingOptionalKey = 1, ///< key not found, but parameter is optional
32+
// Note: errors are != ConfigStatus::OK
33+
FileError = -1, ///< Success
34+
KeyError = -2, ///< key not found, parameter is not optional
35+
ConversionError = -3 /**< Invalid value for conversion
36+
* e.g. wrong-size list for vector, missing
37+
* key 'rows', 'cols' or 'data' (for matrix) */
38+
};
39+
40+
/** Base class representing a parameter to be parsed in the yaml file */
41+
struct ConfigParamBase {
42+
ConfigParamBase(std::string key, bool optional)
43+
: key{std::move(key)}, optional{optional} {};
44+
45+
46+
/** Parse the given node as T, and write the value into `destination`.
47+
* @note no lookup by key is performed; the node must already be correct
48+
* @throws YAML::BadConversion if node is not convertible to destination
49+
*/
50+
virtual void load(const YAML::Node &node) const = 0;
51+
52+
std::string key; //!< yaml key to parse from
53+
bool optional; //!< if true, it is not an error if the key is not found
54+
55+
protected:
56+
~ConfigParamBase() = default; // disallow deletion through pointer to base
6557
};
6658

6759
/** Represents a parameter to be parsed in the yaml file */
68-
class ConfigParam {
60+
template <typename T>
61+
class ConfigParam : public ConfigParamBase {
6962
public:
70-
enum ConfigDataType type = TYPE_NOT_SET; //!< parameter type (e.g `INT`)
71-
std::string key; //!< yaml key to parse from
72-
void *data = nullptr; //!< pointer to variable to store the parameter value
73-
bool optional = false;
63+
ConfigParam(std::string key, T *destination, bool optional = false)
64+
: ConfigParamBase{std::move(key), optional}, data{destination} {}
7465

75-
ConfigParam() {}
66+
/** Parse the given node as T, and write the value into `destination`.
67+
* @note no lookup by key is performed; the node must already be correct
68+
* @throws YAML::BadConversion if node is not convertible to destination
69+
*/
70+
void load(const YAML::Node &node) const override {
71+
*(this->data) = node.as<T>();
72+
}
7673

77-
ConfigParam(ConfigDataType type, std::string key, void *out, bool optional)
78-
: type{type}, key{key}, data{out}, optional{optional} {};
74+
protected:
75+
T *data = nullptr; //!< where we will store the parsed value
7976
};
8077

8178
/** Parses yaml files for parameters of different types.
@@ -115,7 +112,7 @@ class ConfigParser {
115112
bool config_loaded;
116113

117114
YAML::Node root;
118-
std::vector<ConfigParam> params;
115+
std::vector<std::shared_ptr<ConfigParamBase>> params;
119116

120117
/** Default constructor. By default it sets:
121118
*
@@ -131,93 +128,126 @@ class ConfigParser {
131128
* `optional` parameter to define whether `ConfigParser` should fail if the
132129
* parameter is not found.
133130
*/
134-
void addParam(std::string key, bool *out, bool optional = false);
135-
void addParam(std::string key, int *out, bool optional = false);
136-
void addParam(std::string key, float *out, bool optional = false);
137-
void addParam(std::string key, double *out, bool optional = false);
138-
void addParam(std::string key, std::string *out, bool optional = false);
139-
void addParam(std::string key,
140-
std::vector<bool> *out,
141-
bool optional = false);
142-
void addParam(std::string key,
143-
std::vector<int> *out,
144-
bool optional = false);
145-
void addParam(std::string key,
146-
std::vector<float> *out,
147-
bool optional = false);
148-
void addParam(std::string key,
149-
std::vector<double> *out,
150-
bool optional = false);
151-
void addParam(std::string key,
152-
std::vector<std::string> *out,
153-
bool optional = false);
154-
void addParam(std::string key, Vec2 *out, bool optional = false);
155-
void addParam(std::string key, Vec3 *out, bool optional = false);
156-
void addParam(std::string key, Vec4 *out, bool optional = false);
157-
void addParam(std::string key, VecX *out, bool optional = false);
158-
void addParam(std::string key, Mat2 *out, bool optional = false);
159-
void addParam(std::string key, Mat3 *out, bool optional = false);
160-
void addParam(std::string key, Mat4 *out, bool optional = false);
161-
void addParam(std::string key, MatX *out, bool optional = false);
162-
void addParam(std::string key, cv::Mat *out, bool optional = false);
131+
template <typename T>
132+
void addParam(std::string key, T *out, bool optional = false) {
133+
auto ptr =
134+
std::make_shared<ConfigParam<T>>(std::move(key), out, optional);
135+
this->params.push_back(ptr);
136+
}
163137

164138
/** Get yaml node given yaml `key`. The result is assigned to `node` if
165139
* `key` matches anything in the config file, else `node` is set to `NULL`.
166140
*/
167-
int getYamlNode(std::string key, YAML::Node &node);
168-
169-
/** @return a status code meaning
170-
* - `0`: On success
171-
* - `-1`: Config file is not loaded
172-
* - `-2`: `key` not found in yaml file, parameter is not optional
173-
* - `-3`: `key` not found in yaml file, parameter is optional
174-
* - `-4`: Invalid vector (wrong size)
175-
* - `-5`: Invalid matrix (missing yaml key 'rows', 'cols' or 'data' for
176-
* matrix)
177-
*/
178-
/** @return see `getYamlNode` */
179-
int checkKey(std::string key, bool optional);
180-
181-
/** @return see `checkKey`
141+
ConfigStatus getYamlNode(const std::string &key, YAML::Node &node);
142+
143+
/** Check whether a key is present in the yaml file */
144+
ConfigStatus checkKey(const std::string &key, bool optional);
145+
146+
/** Load yaml param primitive, array, vector or matrix. */
147+
ConfigStatus loadParam(const ConfigParamBase &param);
148+
149+
/** Load yaml file at `config_file`. */
150+
ConfigStatus load(const std::string &config_file);
151+
};
152+
153+
/** @} group utils */
154+
} // namespace wave
155+
156+
157+
namespace YAML {
158+
159+
/** Custom conversion functions for YAML -> Eigen matrix
160+
*
161+
* @note We require the yaml node to have three nested keys in order to parse a
162+
* matrix. They are `rows`, `cols` and `data`.
163+
*
164+
* For example:
165+
* ```yaml
166+
* some_matrix:
167+
* rows: 3
168+
* cols: 3
169+
* data: [1.1, 2.2, 3.3,
170+
* 4.4, 5.5, 6.6,
171+
* 7.7, 8.8, 9.9]
172+
* ```
173+
*
174+
* Conversions for the following types are included in of wave_utils:
175+
* - Eigen::Matrix2d
176+
* - Eigen::Matrix3d
177+
* - Eigen::Matrix4d
178+
* - Eigen::MatrixXd
179+
*/
180+
template <typename Scalar, int Rows, int Cols>
181+
struct convert<Eigen::Matrix<Scalar, Rows, Cols>> {
182+
/** Convert YAML node to Eigen Matrix
182183
*
183-
* @todo refactor return codes into an enum which can be documented
184+
* @throws YAML::InvalidNode if nested keys not found
185+
* @returns true if conversion successful
184186
*/
185-
int checkVector(std::string key, enum ConfigDataType type, bool optional);
186-
187-
/** @return see `checkKey` */
188-
int checkMatrix(std::string key, bool optional);
189-
190-
/** Load yaml param primitive, array, vector or matrix.
191-
* @return
192-
* - `0`: On success
193-
* - `-1`: Config file is not loaded
194-
* - `-2`: `key` not found in yaml file, parameter is not optional
195-
* - `-3`: `key` not found in yaml file, parameter is optional
196-
* - `-4`: Invalid vector (wrong size)
197-
* - `-5`: Invalid matrix (missing yaml key 'rows', 'cols' or 'data' for
198-
* matrix)
199-
* - `-6`: Invalid param type
187+
static bool decode(const Node &node,
188+
Eigen::Matrix<Scalar, Rows, Cols> &out);
189+
};
190+
191+
/** Custom conversion functions for YAML -> Eigen vector
192+
*
193+
* For example:
194+
* ```yaml
195+
* some_vector: [1.1, 2.2, 3.3]
196+
* ```
197+
*
198+
* Conversions for the following types are compiled as part of wave_utils:
199+
* - Eigen::Vector2d
200+
* - Eigen::Vector3d
201+
* - Eigen::Vector4d
202+
* - Eigen::VectorXd
203+
*/
204+
template <typename Scalar, int Rows>
205+
struct convert<Eigen::Matrix<Scalar, Rows, 1>> {
206+
/** Convert YAML node to Eigen Matrix
207+
* @returns true if conversion successful
200208
*/
201-
int loadPrimitive(ConfigParam param);
202-
int loadArray(ConfigParam param);
203-
int loadVector(ConfigParam param);
204-
int loadMatrix(ConfigParam param);
205-
206-
/** Load yaml file at `config_file`.
207-
* @return
208-
* - `0`: On success
209-
* - `1`: File not found
210-
* - `-1`: Config file is not loaded
211-
* - `-2`: `key` not found in yaml file
212-
* - `-4`: Invalid vector (wrong size)
213-
* - `-5`: Invalid matrix (missing yaml key 'rows', 'cols' or 'data' for
214-
* matrix)
215-
* - `-6`: Invalid param type
209+
static bool decode(const Node &node, Eigen::Matrix<Scalar, Rows, 1> &out);
210+
};
211+
212+
// Explicit instantiations: include these in the compiled wave_utils library
213+
// Since the function definition is in a .cpp file, other types will not work
214+
template struct convert<wave::Mat2>;
215+
template struct convert<wave::Mat3>;
216+
template struct convert<wave::Mat4>;
217+
template struct convert<wave::MatX>;
218+
template struct convert<wave::Vec2>;
219+
template struct convert<wave::Vec3>;
220+
template struct convert<wave::Vec4>;
221+
template struct convert<wave::VecX>;
222+
223+
224+
/** Custom conversion for YAML -> cv::Mat
225+
*
226+
* @note We require the yaml node to have three nested keys in order to parse a
227+
* matrix. They are `rows`, `cols` and `data`.
228+
*
229+
* For example:
230+
* ```yaml
231+
* some_matrix:
232+
* rows: 3
233+
* cols: 3
234+
* data: [1.1, 2.2, 3.3,
235+
* 4.4, 5.5, 6.6,
236+
* 7.7, 8.8, 9.9]
237+
* ```
238+
*
239+
240+
*/
241+
template <>
242+
struct convert<cv::Mat> {
243+
/** Convert YAML node to cv matrix
244+
*
245+
* @throws YAML::InvalidNode if nested keys not found
246+
* @returns true if conversion successful
216247
*/
217-
int load(std::string config_file);
248+
static bool decode(const Node &node, cv::Mat &out);
218249
};
219250

220-
/** @} group utils */
221-
} // namespace wave
251+
} // namespace YAML
222252

223253
#endif // WAVE_UTILS_CONFIG_HPP

0 commit comments

Comments
 (0)
Please sign in to comment.