settings_generator.cpp
Go to the documentation of this file.
1 // This program generates dynamic_reconfigure .cfg files, as well as c++ header files,
2 // for our settings types (Settings, Settings2D, Settings::Acquisition and
3 // Settings2D::Acquisition). The utility header files are used by the zivid_camera library.
4 // This program is compiled and run during the build stage of the zivid_camera library.
5 
6 #include <Zivid/Settings.h>
7 #include <Zivid/Settings2D.h>
8 
9 #include <dynamic_reconfigure/config_tools.h>
10 
11 #include <boost/algorithm/string.hpp>
12 #include <boost/algorithm/string/replace.hpp>
13 #include <boost/algorithm/string/join.hpp>
14 #include <boost/filesystem.hpp>
15 #include <boost/format.hpp>
16 
17 #include <algorithm>
18 #include <cctype>
19 #include <chrono>
20 #include <fstream>
21 #include <regex>
22 #include <sstream>
23 #include <stdexcept>
24 #include <string>
25 
26 namespace
27 {
28 template <typename T>
29 struct DependentFalse : std::false_type
30 {
31 };
32 
33 template <typename T, typename...>
34 struct IsInList : std::false_type
35 {
36 };
37 
38 template <typename T, typename First, typename... Rest>
39 struct IsInList<T, First, Rest...>
40  : std::integral_constant<bool, std::is_same<T, First>::value || IsInList<T, Rest...>::value>
41 {
42 };
43 
44 template <typename T, typename Tuple>
45 struct IsInTuple;
46 
47 template <typename T, typename... Ts>
48 struct IsInTuple<T, std::tuple<Ts...>> : IsInList<T, Ts...>
49 {
50 };
51 
52 template <typename SettingsNode>
53 struct IsEnumSetting : std::is_enum<typename SettingsNode::ValueType>
54 {
55 };
56 
57 void writeToFile(const std::string& file_name, const std::string& text)
58 {
59  if (boost::filesystem::exists(file_name))
60  {
61  std::ifstream file(file_name);
62  if (!file.is_open())
63  {
64  throw std::runtime_error("Unable to open file '" + file_name + "' to check its contents!");
65  }
66  auto file_contents_ss = std::ostringstream{};
67  file_contents_ss << file.rdbuf();
68  if (file_contents_ss.str() == text)
69  {
70  // If the file already exists, and content is identical to "text" then do not modify the file.
71  // This ensures that we avoid unnecessary rebuilds.
72  return;
73  }
74  }
75 
76  std::ofstream cfg_file(file_name);
77  if (!cfg_file || !cfg_file.is_open())
78  {
79  throw std::runtime_error("Unable to open file '" + file_name + "' for writing!");
80  }
81  cfg_file << text;
82  cfg_file.close();
83  if (!cfg_file)
84  {
85  throw std::runtime_error("Failed to write to file '" + file_name + "'!");
86  }
87 }
88 
89 std::string toUpperCaseFirst(std::string value)
90 {
91  if (value.empty())
92  {
93  throw std::invalid_argument("value is empty");
94  }
95  value[0] = std::toupper(value[0]);
96  return value;
97 }
98 
99 template <typename SettingsRootGroup, typename SettingsNode>
100 std::string convertSettingsPathToConfigPath()
101 {
102  auto path = std::string(SettingsNode::path);
103  const auto root_path = std::string(SettingsRootGroup::path);
104 
105  if (!root_path.empty())
106  {
107  const auto expected_prefix = root_path + "/";
108  if (path.substr(0, expected_prefix.length()) != expected_prefix)
109  {
110  throw std::runtime_error("Expected path '" + path + "' to begin with '" + expected_prefix + "'");
111  }
112  path = path.substr(expected_prefix.length());
113  }
114 
115  path = boost::replace_all_copy<std::string>(path, "/", "_");
116  const std::regex re("([^_^])([A-Z])");
117  path = std::regex_replace(path, re, "$1_$2"); // Convert e.g. ExposureTime to Exposure_Time
118  return boost::algorithm::to_lower_copy(path);
119 }
120 
121 template <typename SettingsRootGroup>
122 std::string zividSettingsTypeName()
123 {
124  if constexpr (std::is_same_v<SettingsRootGroup, Zivid::Settings> ||
125  IsInTuple<SettingsRootGroup, Zivid::Settings::Descendants>::value ||
126  std::is_same_v<SettingsRootGroup, Zivid::Settings::Acquisition> ||
127  IsInTuple<SettingsRootGroup, Zivid::Settings::Acquisition::Descendants>::value)
128  {
129  return Zivid::Settings::name;
130  }
131  else if constexpr (std::is_same_v<SettingsRootGroup, Zivid::Settings2D> ||
132  IsInTuple<SettingsRootGroup, Zivid::Settings2D::Descendants>::value ||
133  std::is_same_v<SettingsRootGroup, Zivid::Settings2D::Acquisition> ||
134  IsInTuple<SettingsRootGroup, Zivid::Settings2D::Acquisition::Descendants>::value)
135  {
136  return Zivid::Settings2D::name;
137  }
138  else
139  {
140  static_assert(DependentFalse<SettingsRootGroup>::value, "Unhandled type.");
141  }
142 }
143 
144 template <typename SettingsNode>
145 std::string fullyQualifiedZividTypeName()
146 {
147  std::stringstream ss;
148  ss << "Zivid::" + zividSettingsTypeName<SettingsNode>();
149  const auto path = std::string(SettingsNode::path);
150  if (!path.empty())
151  {
152  ss << "::" << boost::replace_all_copy<std::string>(path, "/", "::");
153  }
154  return ss.str();
155 }
156 
157 template <typename SettingsNode>
158 std::string settingEnumValueToRosEnumName(typename SettingsNode::ValueType value)
159 {
160  // During build dynamic_reconfigure will auto-generate variables for C++ and Python
161  // for all enum values, scoped directly under the top level .cfg name. So, for example,
162  // an enum value named X listed in Settings.cfg would auto-generate an const int variable
163  // zivid_camera::Settings_X. Since we may have several different enum settings with the
164  // same enum value X, we need to scope the enum name with the full path to the setting.
165  // This ensures there are no collisions now or in the future.
166  const auto value_str = toUpperCaseFirst(SettingsNode{ value }.toString());
167  const auto path = boost::replace_all_copy<std::string>(SettingsNode::path, "/", "");
168  return path + value_str;
169 }
170 
171 template <typename SettingsNode>
172 std::string generateEnumConstant(typename SettingsNode::ValueType value)
173 {
174  static_assert(IsEnumSetting<SettingsNode>::value);
175  const auto name = settingEnumValueToRosEnumName<SettingsNode>(value);
176  const auto int_value = static_cast<std::size_t>(value);
177  const auto description = toUpperCaseFirst(SettingsNode{ value }.toString());
178  return (boost::format(R"(gen.const("%1%", int_t, %2%, "%3%"))") % name % int_value % description).str();
179 }
180 
181 template <typename SettingsRootGroup>
182 class DynamicReconfigureCfgGenerator
183 {
184 public:
185  DynamicReconfigureCfgGenerator(const std::string& class_name) : class_name_(class_name), insert_enabled_(false)
186  {
187  }
188 
189  template <typename SettingsNode>
190  auto cfgFileDefaultValue()
191  {
192  // The default value of settings varies per Zivid camera model. Thus, we cannot set a
193  // correct static hard-coded default value for the setting here. To correctly use the
194  // Zivid driver the user must load the default values via dynamic_reconfigure at runtime.
195  using ValueType = typename SettingsNode::ValueType;
196  if constexpr (std::is_same_v<ValueType, bool>)
197  {
198  return false;
199  }
200  if constexpr (Zivid::DataModel::HasValidRange<SettingsNode>::value)
201  {
202  return SettingsNode::validRange().min();
203  }
204  if constexpr (IsEnumSetting<SettingsNode>::value)
205  {
206  return *SettingsNode::validValues().begin();
207  }
208  return ValueType{ 0 };
209  }
210 
211  template <typename ValueType>
212  auto convertValueToRosValue(ValueType value)
213  {
214  // Convert from our own setting value types to types that ROS params supports (double, int, bool)
215 
216  if constexpr (std::is_same_v<ValueType, bool> || std::is_same_v<ValueType, double>)
217  {
218  return value;
219  }
220  else if constexpr (std::is_same_v<ValueType, std::size_t>)
221  {
222  return static_cast<int>(value);
223  }
224  else if constexpr (std::is_same_v<ValueType, std::chrono::microseconds>)
225  {
226  return static_cast<int>(value.count());
227  }
228  else if constexpr (std::is_enum_v<ValueType>)
229  {
230  return static_cast<int>(value);
231  }
232  else
233  {
234  static_assert(DependentFalse<ValueType>::value, "Could not convert ValueType to ROS type.");
235  }
236  }
237 
238  template <typename RosType>
239  std::string rosTypeName()
240  {
241  if constexpr (std::is_same_v<RosType, bool>)
242  {
243  return "bool_t";
244  }
245  else if constexpr (std::is_same_v<RosType, double>)
246  {
247  return "double_t";
248  }
249  else if constexpr (std::is_same_v<RosType, int>)
250  {
251  return "int_t";
252  }
253  else
254  {
255  static_assert(DependentFalse<RosType>::value, "Could not convert RosType to a ROS typename string.");
256  }
257  }
258 
259  template <typename RosType>
260  std::string rosTypeToString(RosType v)
261  {
262  if constexpr (std::is_same_v<RosType, bool>)
263  {
264  return v ? "True" : "False";
265  }
266  else if constexpr (std::is_same_v<RosType, double> || std::is_same_v<RosType, int>)
267  {
268  return std::to_string(v);
269  }
270  else
271  {
272  static_assert(DependentFalse<RosType>::value, "Could not convert RosType to a string value.");
273  }
274  }
275 
276  template <typename ValueType>
277  std::string valueTypeToRosTypeString(ValueType v)
278  {
279  return rosTypeToString(convertValueToRosValue(v));
280  }
281 
282  std::string rosGeneratedEnumVariableName(const std::string& setting_name)
283  {
284  return setting_name + "_enum";
285  }
286 
287  template <typename SettingsNode>
288  void apply(const SettingsNode& node)
289  {
290  const auto setting_name = convertSettingsPathToConfigPath<SettingsRootGroup, SettingsNode>();
291  const auto level = "0";
292  // Newlines must be converted to \\n so that the auto-generated files end up being correct
293  const auto description = boost::replace_all_copy<std::string>(node.description, "\n", R"(\\n)");
294  const auto default_value = cfgFileDefaultValue<SettingsNode>();
295  const auto type_name = rosTypeName<decltype(convertValueToRosValue(default_value))>();
296  const auto default_value_str = valueTypeToRosTypeString(default_value);
297 
298  if constexpr (IsEnumSetting<SettingsNode>::value)
299  {
300  const auto valid_values = node.validValues();
301  std::vector<std::string> enum_constants;
302  std::transform(valid_values.cbegin(), valid_values.cend(), std::back_inserter(enum_constants),
303  [&](const auto value) { return generateEnumConstant<SettingsNode>(value); });
304  ss_ << rosGeneratedEnumVariableName(setting_name) << " = gen.enum([\n "
305  << boost::algorithm::join(enum_constants, ",\n ") << "\n],\n \"" << description << "\")\n";
306  }
307 
308  ss_ << "gen.add(\"" << setting_name << "\", " << type_name << ", " << level << ", "
309  << "\"" << description << "\", " << default_value_str;
310 
311  if constexpr (Zivid::DataModel::HasValidRange<SettingsNode>::value)
312  {
313  ss_ << ", " << valueTypeToRosTypeString(node.validRange().min()) << ", "
314  << valueTypeToRosTypeString(node.validRange().max());
315  }
316  else if constexpr (IsEnumSetting<SettingsNode>::value)
317  {
318  const auto min_index = 0;
319  const auto max_index = node.validValues().size() - 1;
320  ss_ << ", " << min_index << ", " << max_index << ", edit_method=" << rosGeneratedEnumVariableName(setting_name);
321  }
322  ss_ << ")\n";
323  }
324 
325  void insertEnabled()
326  {
327  insert_enabled_ = true;
328  }
329 
330  std::string str()
331  {
332  std::stringstream res;
333  res << "#!/usr/bin/env python\n\n"
334  "# This is an auto-generated cfg file. Do not edit!\n\n"
335  "PACKAGE = \"zivid_camera\"\n"
336  "import roslib\n"
337  "roslib.load_manifest(PACKAGE);\n"
338  "from dynamic_reconfigure.parameter_generator_catkin import *\n\n";
339 
340  res << "gen = ParameterGenerator()\n";
341  if (insert_enabled_)
342  {
343  res << "gen.add(\"enabled\", bool_t, 0, \"When this acquisition is enabled it will be included in captures\", "
344  "False)\n";
345  }
346  res << ss_.str();
347  res << "gen.generate(PACKAGE, \"zivid_camera\", \"" + class_name_ + "\")\n";
348  return res.str();
349  }
350 
351 private:
352  std::string class_name_;
353  bool insert_enabled_;
354  std::stringstream ss_;
355 };
356 
357 template <typename SettingsRootGroup>
358 class ApplyConfigToZividSettingsGenerator
359 {
360 public:
361  ApplyConfigToZividSettingsGenerator(const std::string& config_class_name) : config_class_name_(config_class_name)
362  {
363  }
364 
365  template <typename SettingsNode>
366  void apply(const SettingsNode& node)
367  {
368  using ValueType = typename SettingsNode::ValueType;
369 
370  const auto cfg_id = "cfg." + convertSettingsPathToConfigPath<SettingsRootGroup, SettingsNode>();
371  const auto setting_node_class_name = fullyQualifiedZividTypeName<SettingsNode>();
372  ss_ << " s.set(" + setting_node_class_name + "{ ";
373 
374  if constexpr (std::is_same_v<ValueType, std::size_t>)
375  {
376  ss_ << "static_cast<std::size_t>(" + cfg_id + ")";
377  }
378  else if constexpr (std::is_same_v<ValueType, std::chrono::microseconds>)
379  {
380  ss_ << "std::chrono::microseconds(" + cfg_id + ")";
381  }
382  else if constexpr (IsEnumSetting<SettingsNode>::value)
383  {
384  ss_ << "\n"
385  << " [value = " + cfg_id + "](){\n"
386  << " switch(value) {\n";
387  const auto valid_values = node.validValues();
388  for (const auto& enum_value : valid_values)
389  {
390  ss_ << " case zivid_camera::" << config_class_name_ << "_"
391  << settingEnumValueToRosEnumName<SettingsNode>(enum_value) << ":\n"
392  << " return " + setting_node_class_name + "::" + SettingsNode{ enum_value }.toString() + ";\n";
393  }
394  ss_ << " };\n"
395  << " throw std::runtime_error(\"Could not convert int value \" + std::to_string(value) + \""
396  << " to setting of type " + setting_node_class_name + ".\");\n"
397  << " }()\n";
398  }
399  else
400  {
401  ss_ << cfg_id;
402  }
403  ss_ << " });\n";
404  }
405 
406  std::string str()
407  {
408  const auto root_type_fq = fullyQualifiedZividTypeName<SettingsRootGroup>();
409 
410  std::stringstream res;
411  res << "inline static void applyConfigToZividSettings(const zivid_camera::" << config_class_name_ << "Config& cfg, "
412  << root_type_fq << "& s)\n";
413  res << "{\n";
414  res << ss_.str();
415  res << "}\n";
416  return res.str();
417  }
418 
419 private:
420  std::string config_class_name_;
421  std::stringstream ss_;
422 };
423 
424 template <typename SettingsRootGroup>
425 class ZividSettingsToConfigGenerator
426 {
427 public:
428  ZividSettingsToConfigGenerator(const std::string& config_class_name) : config_class_name_(config_class_name)
429  {
430  }
431 
432  template <typename SettingsNode>
433  void apply(const SettingsNode&)
434  {
435  using ValueType = typename SettingsNode::ValueType;
436  const auto cfg_id = "cfg." + convertSettingsPathToConfigPath<SettingsRootGroup, SettingsNode>();
437  const auto zivid_node_class_name = fullyQualifiedZividTypeName<SettingsNode>();
438  const auto value_str = "s.get<" + zivid_node_class_name + ">().value()";
439  ss_ << " " + cfg_id + " = ";
440  if constexpr (std::is_same_v<ValueType, std::chrono::microseconds>)
441  {
442  ss_ << "static_cast<int>(" + value_str + ".count());\n";
443  }
444  else if constexpr (std::is_same_v<ValueType, std::size_t>)
445  {
446  ss_ << "static_cast<int>(" + value_str + ");\n";
447  }
448  else if constexpr (IsEnumSetting<SettingsNode>::value)
449  {
450  ss_ << "static_cast<int>(" + value_str + ");\n";
451  }
452  else
453  {
454  ss_ << value_str + ";\n";
455  }
456  }
457 
458  std::string str() const
459  {
460  const auto full_class_name = "zivid_camera::" + config_class_name_ + "Config";
461  const auto root_type_fq = fullyQualifiedZividTypeName<SettingsRootGroup>();
462 
463  std::stringstream res;
464  res << "template<> inline " << full_class_name << " zividSettingsToConfig";
465  res << "<" << full_class_name << ">(const " << root_type_fq << "& s)\n";
466  res << "{\n";
467  res << " auto cfg = " + full_class_name << "::__getDefault__();\n";
468  res << ss_.str();
469  res << " return cfg;\n";
470  res << "}\n";
471  return res.str();
472  }
473 
474 private:
475  std::string config_class_name_;
476  std::stringstream ss_;
477 };
478 
479 template <typename SettingsRootGroup>
480 class MinMaxConfigGenerator
481 {
482 public:
483  enum class Type
484  {
485  Min,
486  Max,
487  };
488 
489  MinMaxConfigGenerator(const std::string& config_class_name, Type type)
490  : config_class_name_(config_class_name), type_(type)
491  {
492  }
493 
494  template <typename SettingsNode>
495  void apply(const SettingsNode&)
496  {
497  if constexpr (Zivid::DataModel::HasValidRange<SettingsNode>::value)
498  {
499  using ValueType = typename SettingsNode::ValueType;
500  const auto cfg_id = "cfg." + convertSettingsPathToConfigPath<SettingsRootGroup, SettingsNode>();
501  const auto zivid_node_class_name = fullyQualifiedZividTypeName<SettingsNode>();
502 
503  const auto value_str = [&]() {
504  std::string prefix =
505  "Zivid::Experimental::SettingsInfo::validRange<" + zivid_node_class_name + ">(camera.info())";
506  switch (type_)
507  {
508  case Type::Min:
509  return prefix + ".min()";
510  case Type::Max:
511  return prefix + ".max()";
512  }
513  throw std::runtime_error(std::string(__func__) + ": Unhandled enum: " + toString(type_));
514  }();
515 
516  ss_ << " " + cfg_id + " = ";
517 
518  if constexpr (std::is_same_v<ValueType, std::chrono::microseconds>)
519  {
520  ss_ << "static_cast<int>(" + value_str + ".count());\n";
521  }
522  else if constexpr (std::is_same_v<ValueType, std::size_t>)
523  {
524  ss_ << "static_cast<int>(" + value_str + ");\n";
525  }
526  else
527  {
528  ss_ << value_str + ";\n";
529  }
530  }
531  }
532 
533  std::string initializeConfigFunction() const
534  {
535  switch (type_)
536  {
537  case Type::Min:
538  return "__getMin__";
539  case Type::Max:
540  return "__getMax__";
541  }
542  throw std::runtime_error(std::string(__func__) + ": Unhandled enum: " + toString(type_));
543  }
544 
545  std::string str() const
546  {
547  const auto full_class_name = "zivid_camera::" + config_class_name_ + "Config";
548 
549  const auto function_name_config_type = [&]() {
550  switch (type_)
551  {
552  case Type::Min:
553  return "Min";
554  case Type::Max:
555  return "Max";
556  }
557  throw std::runtime_error(std::string(__func__) + ": Unhandled enum: " + toString(type_));
558  }();
559 
560  const auto root_type_fq = fullyQualifiedZividTypeName<SettingsRootGroup>();
561 
562  std::stringstream res;
563  res << "template<> inline " << full_class_name << " zividSettings" << function_name_config_type << "Config";
564  res << "<" << full_class_name << ", " << root_type_fq << ">(const Zivid::Camera& camera)\n";
565  res << "{\n";
566  res << " auto cfg = " + full_class_name << "::" << initializeConfigFunction() << "();\n";
567  res << ss_.str();
568  res << " return cfg;\n";
569  res << "}\n";
570  return res.str();
571  }
572 
573  static std::string toString(Type t)
574  {
575  return std::to_string(static_cast<std::underlying_type_t<Type>>(t));
576  }
577 
578 private:
579  std::string config_class_name_;
580  Type type_;
581  std::stringstream ss_;
582 };
583 
584 template <typename SettingsRootGroup>
585 class ConfigUtilsHeaderGenerator
586 {
587 public:
588  ConfigUtilsHeaderGenerator(const std::string& config_class_name)
589  : apply_config_zivid_settings_gen(config_class_name)
590  , zivid_settings_to_config_gen(config_class_name)
591  , min_config_gen(config_class_name, MinMaxConfigGenerator<SettingsRootGroup>::Type::Min)
592  , max_config_gen(config_class_name, MinMaxConfigGenerator<SettingsRootGroup>::Type::Max)
593  {
594  }
595 
596  template <typename SettingsNode>
597  void apply(const SettingsNode& node)
598  {
599  apply_config_zivid_settings_gen.apply(node);
600  zivid_settings_to_config_gen.apply(node);
601  min_config_gen.apply(node);
602  max_config_gen.apply(node);
603  }
604 
605  std::string str()
606  {
607  std::stringstream res;
608  res << "#pragma once\n\n";
609  res << "// This is an auto-generated header. Do not edit.\n\n";
610  res << "#include <Zivid/Camera.h>\n";
611  res << "#include <Zivid/Experimental/SettingsInfo.h>\n\n";
612  res << "#include \"config_utils_common.h\"\n\n";
613 
614  res << apply_config_zivid_settings_gen.str() << "\n";
615  res << zivid_settings_to_config_gen.str() << "\n";
616  res << min_config_gen.str() << "\n";
617  res << max_config_gen.str() << "\n";
618  return res.str();
619  }
620 
621  ApplyConfigToZividSettingsGenerator<SettingsRootGroup> apply_config_zivid_settings_gen;
622  ZividSettingsToConfigGenerator<SettingsRootGroup> zivid_settings_to_config_gen;
623  MinMaxConfigGenerator<SettingsRootGroup> min_config_gen;
624  MinMaxConfigGenerator<SettingsRootGroup> max_config_gen;
625 };
626 
627 template <typename SettingsRootGroup>
628 class Generator
629 {
630 public:
631  Generator(const std::string& config_class_name)
632  : config_class_name_(config_class_name)
633  , dynamic_reconfigure_cfg_gen_(config_class_name)
634  , config_utils_header_gen_(config_class_name)
635  {
636  }
637 
638  template <typename SettingsNode>
639  void apply(const SettingsNode& node)
640  {
641  dynamic_reconfigure_cfg_gen_.apply(node);
642  config_utils_header_gen_.apply(node);
643  }
644 
645  void insertEnabled()
646  {
647  dynamic_reconfigure_cfg_gen_.insertEnabled();
648  }
649 
650  void writeToFiles()
651  {
652  writeToFile(config_class_name_ + ".cfg", dynamic_reconfigure_cfg_gen_.str());
653  writeToFile("generated_headers/" + config_class_name_ + "ConfigUtils.h", config_utils_header_gen_.str());
654  }
655 
656 private:
657  std::string config_class_name_;
658  DynamicReconfigureCfgGenerator<SettingsRootGroup> dynamic_reconfigure_cfg_gen_;
659  ConfigUtilsHeaderGenerator<SettingsRootGroup> config_utils_header_gen_;
660 };
661 
662 template <typename SettingsType, typename SettingsNode, typename GeneratorType>
663 void traverseSettingsTree(const SettingsNode& node, GeneratorType& generator)
664 {
665  if constexpr (std::is_same_v<SettingsNode, typename SettingsType::Acquisitions>)
666  {
667  // Acquisitions ignored here. Acqusitition is handled separately.
668  }
669  else if constexpr (SettingsNode::nodeType == Zivid::DataModel::NodeType::group)
670  {
671  node.forEach([&](const auto& child) { traverseSettingsTree<SettingsType>(child, generator); });
672  }
673  else
674  {
675  generator.apply(node);
676  }
677 }
678 
679 template <typename SettingsType>
680 void addSettingsType(const std::string& cfgPrefix)
681 {
682  Generator<SettingsType> capture_general_gen(cfgPrefix);
683  traverseSettingsTree<SettingsType>(SettingsType{}, capture_general_gen);
684  capture_general_gen.writeToFiles();
685 
686  Generator<typename SettingsType::Acquisition> capture_acquisition_gen(cfgPrefix + "Acquisition");
687  traverseSettingsTree<SettingsType>(typename SettingsType::Acquisition{}, capture_acquisition_gen);
688  capture_acquisition_gen.insertEnabled();
689  capture_acquisition_gen.writeToFiles();
690 }
691 
692 } // namespace
693 
694 int main(int /*argc*/, char** /*argv*/)
695 {
696  addSettingsType<Zivid::Settings>("Settings");
697  addSettingsType<Zivid::Settings2D>("Settings2D");
698  return 0;
699 }
int main(int, char **)
def default_value(type_)


zivid_camera
Author(s): Zivid
autogenerated on Sat Apr 17 2021 02:51:05