opencv_yaml_parse.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OPENCV_YAML_PARSER_H
23 #define OPENCV_YAML_PARSER_H
24 
25 #include <Eigen/Eigen>
26 #include <boost/filesystem.hpp>
27 #include <memory>
28 #include <opencv2/opencv.hpp>
29 
30 #if ROS_AVAILABLE == 1
31 #include <ros/ros.h>
32 #elif ROS_AVAILABLE == 2
33 #include <rclcpp/rclcpp.hpp>
34 #endif
35 
36 #include "colors.h"
37 #include "print.h"
38 #include "quat_ops.h"
39 
40 namespace ov_core {
41 
58 class YamlParser {
59 public:
65  explicit YamlParser(const std::string &config_path, bool fail_if_not_found = true) : config_path_(config_path) {
66 
67  // Check if file exists
68  if (!fail_if_not_found && !boost::filesystem::exists(config_path)) {
69  config = nullptr;
70  return;
71  }
72  if (!boost::filesystem::exists(config_path)) {
73  PRINT_ERROR(RED "unable to open the configuration file!\n%s\n" RESET, config_path.c_str());
74  std::exit(EXIT_FAILURE);
75  }
76 
77  // Open the file, error if we can't
78  config = std::make_shared<cv::FileStorage>(config_path, cv::FileStorage::READ);
79  if (!fail_if_not_found && !config->isOpened()) {
80  config = nullptr;
81  return;
82  }
83  if (!config->isOpened()) {
84  PRINT_ERROR(RED "unable to open the configuration file!\n%s\n" RESET, config_path.c_str());
85  std::exit(EXIT_FAILURE);
86  }
87  }
88 
89 #if ROS_AVAILABLE == 1
90  void set_node_handler(std::shared_ptr<ros::NodeHandle> nh_) { this->nh = nh_; }
92 #endif
93 
94 #if ROS_AVAILABLE == 2
95  void set_node(std::shared_ptr<rclcpp::Node> &node_) { this->node = node_; }
97 #endif
98 
103  std::string get_config_folder() { return config_path_.substr(0, config_path_.find_last_of('/')) + "/"; }
104 
109  bool successful() const { return all_params_found_successfully; }
110 
122  template <class T> void parse_config(const std::string &node_name, T &node_result, bool required = true) {
123 
124 #if ROS_AVAILABLE == 1
125  if (nh != nullptr && nh->getParam(node_name, node_result)) {
126  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, node_name.c_str());
127  nh->param<T>(node_name, node_result);
128  return;
129  }
130 #elif ROS_AVAILABLE == 2
131  if (node != nullptr && node->has_parameter(node_name)) {
132  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, node_name.c_str());
133  node->get_parameter<T>(node_name, node_result);
134  return;
135  }
136 #endif
137 
138  // Else we just parse from the YAML file!
139  parse_config_yaml(node_name, node_result, required);
140  }
141 
157  template <class T>
158  void parse_external(const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name, T &node_result,
159  bool required = true) {
160 
161 #if ROS_AVAILABLE == 1
162  std::string rosnode = sensor_name + "_" + node_name;
163  if (nh != nullptr && nh->getParam(rosnode, node_result)) {
164  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
165  nh->param<T>(rosnode, node_result);
166  return;
167  }
168 #elif ROS_AVAILABLE == 2
169  std::string rosnode = sensor_name + "_" + node_name;
170  if (node != nullptr && node->has_parameter(rosnode)) {
171  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
172  node->get_parameter<T>(rosnode, node_result);
173  return;
174  }
175 #endif
176 
177  // Else we just parse from the YAML file!
178  parse_external_yaml(external_node_name, sensor_name, node_name, node_result, required);
179  }
180 
195  void parse_external(const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name,
196  Eigen::Matrix3d &node_result, bool required = true) {
197 
198 #if ROS_AVAILABLE == 1
199  // If we have the ROS parameter, we should just get that one
200  // NOTE: for our 3x3 matrix we should read it as an array from ROS then covert it back into the 3x3
201  std::string rosnode = sensor_name + "_" + node_name;
202  std::vector<double> matrix_RCtoI;
203  if (nh != nullptr && nh->getParam(rosnode, matrix_RCtoI)) {
204  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
205  nh->param<std::vector<double>>(rosnode, matrix_RCtoI);
206  node_result << matrix_RCtoI.at(0), matrix_RCtoI.at(1), matrix_RCtoI.at(2), matrix_RCtoI.at(3), matrix_RCtoI.at(4), matrix_RCtoI.at(5),
207  matrix_RCtoI.at(6), matrix_RCtoI.at(7), matrix_RCtoI.at(8);
208  return;
209  }
210 #elif ROS_AVAILABLE == 2
211  // If we have the ROS parameter, we should just get that one
212  // NOTE: for our 3x3 matrix we should read it as an array from ROS then covert it back into the 4x4
213  std::string rosnode = sensor_name + "_" + node_name;
214  std::vector<double> matrix_RCtoI;
215  if (node != nullptr && node->has_parameter(rosnode)) {
216  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
217  node->get_parameter<std::vector<double>>(rosnode, matrix_RCtoI);
218  node_result << matrix_RCtoI.at(0), matrix_RCtoI.at(1), matrix_RCtoI.at(2), matrix_RCtoI.at(3), matrix_RCtoI.at(4), matrix_RCtoI.at(5),
219  matrix_RCtoI.at(6), matrix_RCtoI.at(7), matrix_RCtoI.at(8);
220  return;
221  }
222 #endif
223 
224  // Else we just parse from the YAML file!
225  parse_external_yaml(external_node_name, sensor_name, node_name, node_result, required);
226  }
227 
242  void parse_external(const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name,
243  Eigen::Matrix4d &node_result, bool required = true) {
244 
245 #if ROS_AVAILABLE == 1
246  // If we have the ROS parameter, we should just get that one
247  // NOTE: for our 4x4 matrix we should read it as an array from ROS then covert it back into the 4x4
248  std::string rosnode = sensor_name + "_" + node_name;
249  std::vector<double> matrix_TCtoI;
250  if (nh != nullptr && nh->getParam(rosnode, matrix_TCtoI)) {
251  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
252  nh->param<std::vector<double>>(rosnode, matrix_TCtoI);
253  node_result << matrix_TCtoI.at(0), matrix_TCtoI.at(1), matrix_TCtoI.at(2), matrix_TCtoI.at(3), matrix_TCtoI.at(4), matrix_TCtoI.at(5),
254  matrix_TCtoI.at(6), matrix_TCtoI.at(7), matrix_TCtoI.at(8), matrix_TCtoI.at(9), matrix_TCtoI.at(10), matrix_TCtoI.at(11),
255  matrix_TCtoI.at(12), matrix_TCtoI.at(13), matrix_TCtoI.at(14), matrix_TCtoI.at(15);
256  return;
257  }
258 #elif ROS_AVAILABLE == 2
259  // If we have the ROS parameter, we should just get that one
260  // NOTE: for our 4x4 matrix we should read it as an array from ROS then covert it back into the 4x4
261  std::string rosnode = sensor_name + "_" + node_name;
262  std::vector<double> matrix_TCtoI;
263  if (node != nullptr && node->has_parameter(rosnode)) {
264  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
265  node->get_parameter<std::vector<double>>(rosnode, matrix_TCtoI);
266  node_result << matrix_TCtoI.at(0), matrix_TCtoI.at(1), matrix_TCtoI.at(2), matrix_TCtoI.at(3), matrix_TCtoI.at(4), matrix_TCtoI.at(5),
267  matrix_TCtoI.at(6), matrix_TCtoI.at(7), matrix_TCtoI.at(8), matrix_TCtoI.at(9), matrix_TCtoI.at(10), matrix_TCtoI.at(11),
268  matrix_TCtoI.at(12), matrix_TCtoI.at(13), matrix_TCtoI.at(14), matrix_TCtoI.at(15);
269  return;
270  }
271 #endif
272 
273  // Else we just parse from the YAML file!
274  parse_external_yaml(external_node_name, sensor_name, node_name, node_result, required);
275  }
276 
277 #if ROS_AVAILABLE == 2
278  void parse_config(const std::string &node_name, int &node_result, bool required = true) {
281  int64_t val = node_result;
282  if (node != nullptr && node->has_parameter(node_name)) {
283  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, node_name.c_str());
284  node->get_parameter<int64_t>(node_name, val);
285  node_result = (int)val;
286  return;
287  }
288  parse_config_yaml(node_name, node_result, required);
289  }
292  void parse_external(const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name,
293  std::vector<int> &node_result, bool required = true) {
294  std::vector<int64_t> val;
295  for (auto tmp : node_result)
296  val.push_back(tmp);
297  std::string rosnode = sensor_name + "_" + node_name;
298  if (node != nullptr && node->has_parameter(rosnode)) {
299  PRINT_INFO(GREEN "overriding node " BOLDGREEN "%s" RESET GREEN " with value from ROS!\n" RESET, rosnode.c_str());
300  node->get_parameter<std::vector<int64_t>>(rosnode, val);
301  node_result.clear();
302  for (auto tmp : val)
303  node_result.push_back((int)tmp);
304  return;
305  }
306  parse_external_yaml(external_node_name, sensor_name, node_name, node_result, required);
307  }
308 #endif
309 
310 private:
312  std::string config_path_;
313 
315  std::shared_ptr<cv::FileStorage> config;
316 
319 
320 #if ROS_AVAILABLE == 1
321  std::shared_ptr<ros::NodeHandle> nh;
323 #endif
324 
325 #if ROS_AVAILABLE == 2
326  std::shared_ptr<rclcpp::Node> node = nullptr;
328 #endif
329 
336  static bool node_found(const cv::FileNode &file_node, const std::string &node_name) {
337  bool found_node = false;
338  for (const auto &item : file_node) {
339  if (item.name() == node_name) {
340  found_node = true;
341  }
342  }
343  return found_node;
344  }
345 
357  template <class T> void parse(const cv::FileNode &file_node, const std::string &node_name, T &node_result, bool required = true) {
358 
359  // Check that we have the requested node
360  if (!node_found(file_node, node_name)) {
361  if (required) {
362  PRINT_WARNING(YELLOW "the node %s of type [%s] was not found...\n" RESET, node_name.c_str(), typeid(node_result).name());
364  } else {
365  PRINT_DEBUG("the node %s of type [%s] was not found (not required)...\n", node_name.c_str(), typeid(node_result).name());
366  }
367  return;
368  }
369 
370  // Now try to get it from the config
371  try {
372  file_node[node_name] >> node_result;
373  } catch (...) {
374  if (required) {
375  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in the config file!\n" RESET, node_name.c_str(),
376  typeid(node_result).name());
378  } else {
379  PRINT_DEBUG("unable to parse %s node of type [%s] in the config file (not required)\n", node_name.c_str(),
380  typeid(node_result).name());
381  }
382  }
383  }
384 
392  void parse(const cv::FileNode &file_node, const std::string &node_name, bool &node_result, bool required = true) {
393 
394  // Check that we have the requested node
395  if (!node_found(file_node, node_name)) {
396  if (required) {
397  PRINT_WARNING(YELLOW "the node %s of type [%s] was not found...\n" RESET, node_name.c_str(), typeid(node_result).name());
399  } else {
400  PRINT_DEBUG("the node %s of type [%s] was not found (not required)...\n", node_name.c_str(), typeid(node_result).name());
401  }
402  return;
403  }
404 
405  // Now try to get it from the config
406  try {
407  if (file_node[node_name].isInt() && (int)file_node[node_name] == 1) {
408  node_result = true;
409  return;
410  }
411  if (file_node[node_name].isInt() && (int)file_node[node_name] == 0) {
412  node_result = false;
413  return;
414  }
415  // NOTE: we select the first bit of text as there can be a comment afterwards
416  // NOTE: for example we could have "key: true #comment here..." where we only want "true"
417  std::string value;
418  file_node[node_name] >> value;
419  value = value.substr(0, value.find_first_of('#'));
420  value = value.substr(0, value.find_first_of(' '));
421  if (value == "1" || value == "true" || value == "True" || value == "TRUE") {
422  node_result = true;
423  } else if (value == "0" || value == "false" || value == "False" || value == "FALSE") {
424  node_result = false;
425  } else {
426  PRINT_WARNING(YELLOW "the node %s has an invalid boolean type of [%s]\n" RESET, node_name.c_str(), value.c_str());
428  }
429  } catch (...) {
430  if (required) {
431  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in the config file!\n" RESET, node_name.c_str(),
432  typeid(node_result).name());
434  } else {
435  PRINT_DEBUG("unable to parse %s node of type [%s] in the config file (not required)\n", node_name.c_str(),
436  typeid(node_result).name());
437  }
438  }
439  }
440 
448  void parse(const cv::FileNode &file_node, const std::string &node_name, Eigen::Matrix3d &node_result, bool required = true) {
449 
450  // Check that we have the requested node
451  if (!node_found(file_node, node_name)) {
452  if (required) {
453  PRINT_WARNING(YELLOW "the node %s of type [%s] was not found...\n" RESET, node_name.c_str(), typeid(node_result).name());
455  } else {
456  PRINT_DEBUG("the node %s of type [%s] was not found (not required)...\n", node_name.c_str(), typeid(node_result).name());
457  }
458  return;
459  }
460 
461  // Now try to get it from the config
462  node_result = Eigen::Matrix3d::Identity();
463  try {
464  for (int r = 0; r < (int)file_node[node_name].size() && r < 3; r++) {
465  for (int c = 0; c < (int)file_node[node_name][r].size() && c < 3; c++) {
466  node_result(r, c) = (double)file_node[node_name][r][c];
467  }
468  }
469  } catch (...) {
470  if (required) {
471  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in the config file!\n" RESET, node_name.c_str(),
472  typeid(node_result).name());
474  } else {
475  PRINT_DEBUG("unable to parse %s node of type [%s] in the config file (not required)\n", node_name.c_str(),
476  typeid(node_result).name());
477  }
478  }
479  }
480 
488  void parse(const cv::FileNode &file_node, const std::string &node_name, Eigen::Matrix4d &node_result, bool required = true) {
489 
490  // See if we need to flip the node name
491  std::string node_name_local = node_name;
492  if (node_name == "T_cam_imu" && !node_found(file_node, node_name)) {
493  PRINT_INFO("parameter T_cam_imu not found, trying T_imu_cam instead (will return T_cam_imu still)!\n");
494  node_name_local = "T_imu_cam";
495  } else if (node_name == "T_imu_cam" && !node_found(file_node, node_name)) {
496  PRINT_INFO("parameter T_imu_cam not found, trying T_cam_imu instead (will return T_imu_cam still)!\n");
497  node_name_local = "T_cam_imu";
498  }
499 
500  // Check that we have the requested node
501  if (!node_found(file_node, node_name_local)) {
502  if (required) {
503  PRINT_WARNING(YELLOW "the node %s of type [%s] was not found...\n" RESET, node_name_local.c_str(), typeid(node_result).name());
505  } else {
506  PRINT_DEBUG("the node %s of type [%s] was not found (not required)...\n", node_name_local.c_str(), typeid(node_result).name());
507  }
508  return;
509  }
510 
511  // Now try to get it from the config
512  node_result = Eigen::Matrix4d::Identity();
513  try {
514  for (int r = 0; r < (int)file_node[node_name_local].size() && r < 4; r++) {
515  for (int c = 0; c < (int)file_node[node_name_local][r].size() && c < 4; c++) {
516  node_result(r, c) = (double)file_node[node_name_local][r][c];
517  }
518  }
519  } catch (...) {
520  if (required) {
521  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in the config file!\n" RESET, node_name.c_str(),
522  typeid(node_result).name());
524  } else {
525  PRINT_DEBUG("unable to parse %s node of type [%s] in the config file (not required)\n", node_name.c_str(),
526  typeid(node_result).name());
527  }
528  }
529 
530  // Finally if we flipped the transform, get the correct value
531  if (node_name_local != node_name) {
532  Eigen::Matrix4d tmp(node_result);
533  node_result = ov_core::Inv_se3(tmp);
534  }
535  }
536 
548  template <class T> void parse_config_yaml(const std::string &node_name, T &node_result, bool required = true) {
549 
550  // Directly return if the config hasn't been opened
551  if (config == nullptr)
552  return;
553 
554  // Else lets get the one from the config
555  try {
556  parse(config->root(), node_name, node_result, required);
557  } catch (...) {
558  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in the config file!\n" RESET, node_name.c_str(),
559  typeid(node_result).name());
561  }
562  }
563 
579  template <class T>
580  void parse_external_yaml(const std::string &external_node_name, const std::string &sensor_name, const std::string &node_name,
581  T &node_result, bool required = true) {
582  // Directly return if the config hasn't been opened
583  if (config == nullptr)
584  return;
585 
586  // Create the path the external yaml file
587  std::string path;
588  if (!node_found(config->root(), external_node_name)) {
589  PRINT_ERROR(RED "the external node %s could not be found!\n" RESET, external_node_name.c_str());
590  std::exit(EXIT_FAILURE);
591  }
592  (*config)[external_node_name] >> path;
593  std::string relative_folder = config_path_.substr(0, config_path_.find_last_of('/')) + "/";
594 
595  // Now actually try to load them from file!
596  auto config_external = std::make_shared<cv::FileStorage>(relative_folder + path, cv::FileStorage::READ);
597  if (!config_external->isOpened()) {
598  PRINT_ERROR(RED "unable to open the configuration file!\n%s\n" RESET, (relative_folder + path).c_str());
599  std::exit(EXIT_FAILURE);
600  }
601 
602  // Check that we have the requested node
603  if (!node_found(config_external->root(), sensor_name)) {
604  PRINT_WARNING(YELLOW "the sensor %s of type [%s] was not found...\n" RESET, sensor_name.c_str(), typeid(node_result).name());
606  return;
607  }
608 
609  // Else lets get it!
610  try {
611  parse((*config_external)[sensor_name], node_name, node_result, required);
612  } catch (...) {
613  PRINT_WARNING(YELLOW "unable to parse %s node of type [%s] in [%s] in the external %s config file!\n" RESET, node_name.c_str(),
614  typeid(node_result).name(), sensor_name.c_str(), external_node_name.c_str());
616  }
617  }
618 };
619 
620 } /* namespace ov_core */
621 
622 #endif /* OPENCV_YAML_PARSER_H */
ov_core::YamlParser::successful
bool successful() const
Check to see if all parameters were read succesfully.
Definition: opencv_yaml_parse.h:109
ov_core::YamlParser::parse_config
void parse_config(const std::string &node_name, T &node_result, bool required=true)
Custom parser for the ESTIMATOR parameters.
Definition: opencv_yaml_parse.h:122
ov_core::YamlParser::parse
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.
Definition: opencv_yaml_parse.h:357
ov_core::YamlParser::YamlParser
YamlParser(const std::string &config_path, bool fail_if_not_found=true)
Constructor that loads all three configuration files.
Definition: opencv_yaml_parse.h:65
ov_core::YamlParser::parse_config_yaml
void parse_config_yaml(const std::string &node_name, T &node_result, bool required=true)
Custom parser for the ESTIMATOR parameters.
Definition: opencv_yaml_parse.h:548
ov_core::YamlParser::config_path_
std::string config_path_
Path to the config file.
Definition: opencv_yaml_parse.h:312
GREEN
#define GREEN
Definition: colors.h:28
ros.h
PRINT_DEBUG
#define PRINT_DEBUG(x...)
Definition: print.h:97
PRINT_ERROR
#define PRINT_ERROR(x...)
Definition: print.h:100
ov_core::YamlParser::parse
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)
Definition: opencv_yaml_parse.h:392
ov_core::YamlParser::parse_external_yaml
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.
Definition: opencv_yaml_parse.h:580
ov_core::YamlParser::node_found
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.
Definition: opencv_yaml_parse.h:336
ov_core::YamlParser::parse_external
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.
Definition: opencv_yaml_parse.h:242
print.h
ov_core::YamlParser::parse_external
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.
Definition: opencv_yaml_parse.h:195
ov_core::YamlParser::config
std::shared_ptr< cv::FileStorage > config
Our config file with the data in it.
Definition: opencv_yaml_parse.h:315
RED
#define RED
Definition: colors.h:27
colors.h
ov_core::YamlParser::parse_external
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.
Definition: opencv_yaml_parse.h:158
ov_core::YamlParser::get_config_folder
std::string get_config_folder()
Will get the folder this config file is in.
Definition: opencv_yaml_parse.h:103
ov_core::YamlParser::all_params_found_successfully
bool all_params_found_successfully
Record if all parameters were found.
Definition: opencv_yaml_parse.h:318
PRINT_INFO
#define PRINT_INFO(x...)
Definition: print.h:98
ov_core::YamlParser
Helper class to do OpenCV yaml parsing from both file and ROS.
Definition: opencv_yaml_parse.h:58
RESET
#define RESET
Definition: colors.h:25
ov_core::YamlParser::parse
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.
Definition: opencv_yaml_parse.h:488
quat_ops.h
ov_core::Inv_se3
Eigen::Matrix4d Inv_se3(const Eigen::Matrix4d &T)
SE(3) matrix analytical inverse.
Definition: quat_ops.h:439
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30
YELLOW
#define YELLOW
Definition: colors.h:29
PRINT_WARNING
#define PRINT_WARNING(x...)
Definition: print.h:99
ov_core::YamlParser::parse
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.
Definition: opencv_yaml_parse.h:448
BOLDGREEN
#define BOLDGREEN
Definition: colors.h:37


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:46