Configuration.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2019 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
8 #include <mc_rtc/deprecated.h>
9 
10 #include <mc_rbdyn/Gains.h>
11 #include <mc_rbdyn/rpy_utils.h>
12 
13 #include <SpaceVecAlg/SpaceVecAlg>
14 
15 #include <Eigen/Core>
16 #include <spdlog/fmt/fmt.h>
17 
18 #include <array>
19 #include <exception>
20 #include <map>
21 #include <memory>
22 #include <optional>
23 #include <set>
24 #include <string>
25 #include <string_view>
26 #include <unordered_set>
27 #include <variant>
28 #include <vector>
29 
30 // The code we use to convert a Configuration value to an std::variant value requires GCC >= 8.3
31 // We use a less optimal recursive implementation for the case where GCC < 8.3
32 #if defined(__GNUC__) && !defined(__llvm__) && !defined(__INTEL_COMPILER)
33 # if __GNUC__ > 8 || (__GNUC__ == 8 && __GNUC_MINOR__ > 2)
34 # define MC_RTC_USE_VARIANT_WORKAROUND 0
35 # else
36 # define MC_RTC_USE_VARIANT_WORKAROUND 1
37 # endif
38 #else
39 # define MC_RTC_USE_VARIANT_WORKAROUND 0
40 #endif
41 
42 namespace mc_rtc
43 {
44 
47 
54 template<typename T>
56 {
57  static void load(const mc_rtc::Configuration &) {}
58 
59  static void save(const T &) {}
60 };
61 
62 template<>
63 struct ConfigurationLoader<void>
64 {
65  static void load(const mc_rtc::Configuration &) {}
66  static void save() {}
67 };
68 
69 namespace internal
70 {
76 {
77  template<typename T,
78  typename std::enable_if<
79  std::is_same<decltype(ConfigurationLoader<T>::load(std::declval<const Configuration &>())), T>::value,
80  int>::type = 0>
81  static std::true_type test(T * p);
82 
83  template<typename T>
84  static std::false_type test(...);
85 };
86 
87 template<typename T>
88 inline constexpr bool has_configuration_load_object_v =
89  decltype(_has_configuration_load_object::test<T>(nullptr))::value;
90 
96 {
97  template<typename T,
98  typename = std::enable_if_t<
99  std::is_same_v<decltype(T::fromConfiguration(std::declval<const Configuration &>())), T>>>
100  static std::true_type test(T * p);
101 
102  template<typename T>
103  static std::false_type test(...);
104 };
105 
106 template<typename T>
107 inline constexpr bool has_static_fromConfiguration_v = decltype(_has_static_fromConfiguration::test<T>(nullptr))::value;
108 
114 {
115  template<typename T,
116  typename... Args,
117  typename std::enable_if<
118  std::is_same<decltype(ConfigurationLoader<T>::save(std::declval<const T &>(), std::declval<Args>()...)),
119  Configuration>::value,
120  int>::type = 0>
121  static std::true_type test(T * p);
122 
123  template<typename T, typename... Args>
124  static std::false_type test(...);
125 };
126 
127 template<typename T, typename... Args>
128 inline constexpr bool has_configuration_save_object_v =
129  decltype(_has_configuration_save_object::test<T, Args...>(nullptr))::value;
130 
136 {
137  template<
138  typename T,
139  typename... Args,
140  typename = std::enable_if_t<
141  std::is_same_v<decltype(std::declval<const T &>().toConfiguration(std::declval<Args>()...)), Configuration>>>
142  static std::true_type test(T * p);
143 
144  template<typename T, typename... Args>
145  static std::false_type test(...);
146 };
147 
148 template<typename T, typename... Args>
149 inline constexpr bool has_toConfiguration_method_v =
150  decltype(_has_toConfiguration_method::test<T, Args...>(nullptr))::value;
151 
152 #if MC_RTC_USE_VARIANT_WORKAROUND
153 
154 template<size_t IDX, typename... Args>
155 std::variant<Args...> to_variant(const Configuration & c, size_t idx);
156 #endif
157 
158 } // namespace internal
159 
166 {
167 private:
173  struct MC_RTC_UTILS_DLLAPI Json
174  {
176  bool isArray() const noexcept;
178  size_t size() const noexcept;
183  Json operator[](size_t idx) const;
185  bool isObject() const noexcept;
187  std::vector<std::string> keys() const noexcept;
192  Json operator[](const std::string & key) const;
194  std::optional<Json> find(const std::string & key) const;
196  bool isString() const noexcept;
198  bool isNumeric() const noexcept;
203  double asDouble() const;
208  void path(std::string & out) const noexcept;
210  void * value_;
212  std::shared_ptr<void> doc_;
213  };
214 
215 public:
223  struct MC_RTC_UTILS_DLLAPI Exception : public std::exception
224  {
231  Exception(const std::string & msg, const Json & v);
232 
239  Exception(const std::string & msg, const Configuration & c) : Exception(msg, c.v) {}
240 
241  ~Exception() noexcept;
242 
244  virtual const char * what() const noexcept override;
245 
247  void silence() const noexcept;
248 
250  const std::string & msg() const noexcept;
251 
252  private:
253  mutable std::string msg_;
254  mutable Json v_;
255  };
256 
263  MC_RTC_DEPRECATED bool isMember(const std::string & key) const;
264 
271  bool has(const std::string & key) const;
272 
277  operator bool() const;
278 
285  operator int8_t() const;
286 
294  operator uint8_t() const;
295 
302  operator int16_t() const;
303 
311  operator uint16_t() const;
312 
319  operator int32_t() const;
320 
328  operator uint32_t() const;
329 
336  operator int64_t() const;
337 
345  operator uint64_t() const;
346 
353  operator double() const;
354 
365  operator std::string() const;
366 
372  operator Eigen::Vector2d() const;
373 
379  operator Eigen::Vector3d() const;
380 
386  operator Eigen::Vector4d() const;
387 
393  operator Eigen::Vector6d() const;
394 
399  operator mc_rbdyn::Gains2d() const;
400 
405  operator mc_rbdyn::Gains3d() const;
406 
411  operator mc_rbdyn::Gains6d() const;
412 
421  operator Eigen::VectorXd() const;
422 
430  operator Eigen::Quaterniond() const;
431 
437  operator Eigen::Matrix3d() const;
438 
443  operator Eigen::Matrix6d() const;
444 
449  operator Eigen::MatrixXd() const;
450 
455  operator sva::PTransformd() const;
456 
461  operator sva::ForceVecd() const;
462 
467  operator sva::MotionVecd() const;
468 
473  operator sva::ImpedanceVecd() const;
474 
481  template<class T, class A>
482  operator std::vector<T, A>() const
483  {
484  if(v.isArray())
485  {
486  std::vector<T, A> ret;
487  for(size_t i = 0; i < v.size(); ++i) { ret.push_back(Configuration(v[i])); }
488  return ret;
489  }
490  throw Configuration::Exception("Stored Json value is not a vector", v);
491  }
492 
499  template<class T, std::size_t N>
500  operator std::array<T, N>() const
501  {
502  if(v.isArray() && v.size() == N)
503  {
504  std::array<T, N> ret;
505  for(size_t i = 0; i < N; ++i) { ret[i] = Configuration(v[i]); }
506  return ret;
507  }
508  throw Configuration::Exception("Stored Json value is not an array or its size is incorrect", v);
509  }
510 
516  template<class T1, class T2>
517  operator std::pair<T1, T2>() const
518  {
519  if(v.isArray() && v.size() == 2) { return std::make_pair<T1, T2>(Configuration(v[0]), Configuration(v[1])); }
520  throw Configuration::Exception("Stored Json value is not an array of size 2", v);
521  }
522 
528  template<typename T, class C, class A>
529  operator std::map<std::string, T, C, A>() const
530  {
531  if(v.isObject())
532  {
533  std::map<std::string, T, C, A> ret;
534  auto keys = v.keys();
535  assert(std::set<std::string>(keys.begin(), keys.end()).size() == keys.size());
536  for(const auto & k : keys)
537  {
538  T value = Configuration(v[k]);
539  ret[k] = value;
540  }
541  return ret;
542  }
543  throw Configuration::Exception("Stored Json value is not an object", v);
544  }
545 
552  template<typename T, typename C = std::less<T>, typename A = std::allocator<T>>
553  operator std::set<T, C, A>() const
554  {
555  if(v.isArray())
556  {
557  std::set<T, C, A> ret;
558  for(size_t i = 0; i < v.size(); ++i)
559  {
560  auto ins = ret.insert(Configuration(v[i]));
561  if(!ins.second) { throw Configuration::Exception("Stored Json set does not hold unique values", v); }
562  }
563  return ret;
564  }
565  throw Configuration::Exception("Stored Json value is not an array", v);
566  }
567 
574  template<typename T, typename H = std::hash<T>, typename E = std::equal_to<T>, typename A = std::allocator<T>>
575  operator std::unordered_set<T, H, E, A>() const
576  {
577  if(v.isArray())
578  {
579  std::unordered_set<T, H, E, A> ret;
580  for(size_t i = 0; i < v.size(); ++i)
581  {
582  auto ins = ret.insert(Configuration(v[i]));
583  if(!ins.second) { throw Configuration::Exception("Stored Json set does not hold unique values", v); }
584  }
585  return ret;
586  }
587  throw Configuration::Exception("Stored Json value is not an array", v);
588  }
589 
599  template<typename... Args>
600  operator std::variant<Args...>() const
601  {
602  if(!v.isArray()) { throw Configuration::Exception("Stored Json value is not an array", v); }
603  if(v.size() != 2) { throw Configuration::Exception("Stored Json value is not of size 2", v); }
604  size_t idx = Configuration(v[0]);
605  if(idx >= sizeof...(Args)) { throw Configuration::Exception("Variant index out of type index bound", v); }
606 #if MC_RTC_USE_VARIANT_WORKAROUND
607  return internal::to_variant<0, Args...>(v[1], idx);
608 #else
609  static constexpr auto table =
610  std::array{+[](const Configuration & c) { return std::variant<Args...>{c.operator Args()}; }...};
611  return table[idx](v[1]);
612 #endif
613  }
614 
619  template<typename T, typename std::enable_if<internal::is_integral_v<T>, int>::type = 0>
620  operator T() const
621  {
622  if constexpr(internal::is_like_int8_t<T>) { return static_cast<T>(this->operator int8_t()); }
623  else if constexpr(internal::is_like_int16_t<T>) { return static_cast<T>(this->operator int16_t()); }
624  else if constexpr(internal::is_like_int32_t<T>) { return static_cast<T>(this->operator int32_t()); }
625  else if constexpr(internal::is_like_int64_t<T>) { return static_cast<T>(this->operator int64_t()); }
626  else if constexpr(internal::is_like_uint8_t<T>) { return static_cast<T>(this->operator uint8_t()); }
627  else if constexpr(internal::is_like_uint16_t<T>) { return static_cast<T>(this->operator uint16_t()); }
628  else if constexpr(internal::is_like_uint32_t<T>) { return static_cast<T>(this->operator uint32_t()); }
629  else if constexpr(internal::is_like_uint64_t<T>) { return static_cast<T>(this->operator uint64_t()); }
630  else { static_assert(!std::is_same_v<T, T>, "T is integral but has an unsupported size"); }
631  }
632 
638  template<typename T,
639  typename std::enable_if<internal::has_configuration_load_object_v<T>
640  || internal::has_static_fromConfiguration_v<T>,
641  int>::type = 0>
642  operator T() const
643  {
644  if constexpr(internal::has_configuration_load_object_v<T>) { return ConfigurationLoader<T>::load(*this); }
645  else { return T::fromConfiguration(*this); }
646  }
647 
652  template<typename T>
653  explicit operator std::optional<T>() const
654  {
655  try
656  {
657  return this->convert<T>();
658  }
659  catch(Exception & exc)
660  {
661  exc.silence();
662  return std::nullopt;
663  }
664  }
665 
667  Configuration();
668 
674  Configuration(const std::string & path);
675 
681  Configuration(const char * path);
682 
687  static Configuration rootArray();
688 
694  static Configuration fromData(const std::string & data);
695 
701  static Configuration fromData(const char * data);
702 
708  static Configuration fromYAMLData(const std::string & data);
709 
715  static Configuration fromYAMLData(const char * data);
716 
724  static Configuration fromMessagePack(const char * data, size_t size);
725 
735  void load(const std::string & path);
736 
748  void load(const mc_rtc::Configuration & config);
749 
757  void loadData(const std::string & data);
758 
766  void loadYAMLData(const std::string & data);
767 
777  void save(const std::string & path, bool pretty = true) const;
778 
786  std::string dump(bool pretty = false, bool yaml = false) const;
787 
795  size_t toMessagePack(std::vector<char> & data) const;
796 
804  void toMessagePack(MessagePackBuilder & builder) const;
805 
816  Configuration operator()(const std::string & key) const;
817 
824  std::optional<Configuration> find(const std::string & key) const;
825 
836  template<typename... Args>
837  std::optional<Configuration> find(const std::string & key, Args &&... others) const
838  {
839  auto out = find(key);
840  return out ? out->find(std::forward<Args>(others)...) : std::nullopt;
841  }
842 
853  template<typename T, typename... Args>
854  std::optional<T> find(const std::string & key, Args &&... others) const
855  {
856  auto maybe_cfg = find(key, std::forward<Args>(others)...);
857  if(maybe_cfg) { return maybe_cfg->operator T(); }
858  return std::nullopt;
859  }
860 
862  bool empty() const;
863 
870  size_t size() const;
871 
873  inline bool isArray() const noexcept { return v.isArray(); }
874 
876  inline bool isObject() const noexcept { return v.isObject(); }
877 
879  inline bool isString() const noexcept { return v.isString(); }
880 
882  inline bool isNumeric() const noexcept { return v.isNumeric(); }
883 
891  Configuration operator[](size_t i) const;
892 
901  template<typename T>
902  T at(size_t i, const T & v) const
903  {
904  try
905  {
906  return (*this)[i].convert<T>();
907  }
908  catch(Exception & exc)
909  {
910  exc.silence();
911  return v;
912  }
913  }
914 
927  template<typename T>
928  void operator()(const std::string & key, T & v) const
929  {
930  try
931  {
932  v = (*this)(key).convert<T>();
933  }
934  catch(Exception & exc)
935  {
936  exc.silence();
937  }
938  }
939 
950  template<typename T>
951  T operator()(const std::string & key, const T & v) const
952  {
953  try
954  {
955  return (*this)(key).convert<T>();
956  }
957  catch(Exception & exc)
958  {
959  exc.silence();
960  return v;
961  }
962  }
963 
968  bool operator==(const char * rhs) const;
969 
974  template<typename T>
975  bool operator==(const T & rhs) const
976  {
977  T lhs = *this;
978  return lhs == rhs;
979  }
980 
988  void add_null(const std::string & key);
989 
998  void add(const std::string & key, bool value);
999 
1004  void add(const std::string & key, int8_t value);
1005 
1010  void add(const std::string & key, uint8_t value);
1011 
1016  void add(const std::string & key, int16_t value);
1017 
1022  void add(const std::string & key, uint16_t value);
1023 
1028  void add(const std::string & key, int32_t value);
1029 
1034  void add(const std::string & key, uint32_t value);
1035 
1040  void add(const std::string & key, int64_t value);
1041 
1046  void add(const std::string & key, uint64_t value);
1047 
1052  void add(const std::string & key, double value);
1053 
1058  void add(const std::string & key, const std::string & value);
1059 
1065  void add(const std::string & key, const char * value);
1066 
1071  void add(const std::string & key, const Eigen::Vector2d & value);
1072 
1077  void add(const std::string & key, const Eigen::Vector3d & value);
1078 
1083  void add(const std::string & key, const Eigen::Vector4d & value);
1084 
1089  void add(const std::string & key, const Eigen::Vector6d & value);
1090 
1095  void add(const std::string & key, const Eigen::VectorXd & value);
1096 
1101  void add(const std::string & key, const Eigen::Quaterniond & value);
1102 
1107  void add(const std::string & key, const Eigen::Matrix3d & value);
1108 
1113  void add(const std::string & key, const Eigen::Matrix6d & value);
1114 
1119  void add(const std::string & key, const Eigen::MatrixXd & value);
1120 
1125  void add(const std::string & key, const sva::PTransformd & value);
1126 
1131  void add(const std::string & key, const sva::ForceVecd & value);
1132 
1137  void add(const std::string & key, const sva::MotionVecd & value);
1138 
1143  void add(const std::string & key, const sva::ImpedanceVecd & value);
1144 
1149  void add(const std::string & key, const Configuration & value);
1150 
1157  Configuration add(const std::string & key);
1158 
1167  Configuration array(const std::string & key, size_t size = 0);
1168 
1173  void push_null();
1174 
1181  void push(bool value);
1182 
1187  void push(int8_t value);
1188 
1193  void push(uint8_t value);
1194 
1199  void push(int16_t value);
1200 
1205  void push(uint16_t value);
1206 
1211  void push(int32_t value);
1212 
1217  void push(uint32_t value);
1218 
1223  void push(int64_t value);
1224 
1229  void push(uint64_t value);
1230 
1235  void push(double value);
1236 
1241  void push(const std::string & value);
1242 
1247  void push(const char * value);
1248 
1253  void push(const Eigen::Vector2d & value);
1254 
1259  void push(const Eigen::Vector3d & value);
1260 
1265  void push(const Eigen::Vector4d & value);
1266 
1271  void push(const Eigen::Vector6d & value);
1272 
1277  void push(const Eigen::VectorXd & value);
1278 
1283  void push(const Eigen::Quaterniond & value);
1284 
1289  void push(const Eigen::Matrix3d & value);
1290 
1295  void push(const Eigen::Matrix6d & value);
1296 
1301  void push(const Eigen::MatrixXd & value);
1302 
1307  void push(const sva::PTransformd & value);
1308 
1313  void push(const sva::ForceVecd & value);
1314 
1319  void push(const sva::MotionVecd & value);
1320 
1325  void push(const sva::ImpedanceVecd & value);
1326 
1331  void push(const Configuration & value);
1332 
1337  Configuration array(size_t reserve = 0);
1338 
1343  Configuration object();
1344 
1352  template<typename T,
1353  typename... Args,
1354  typename std::enable_if<internal::has_configuration_save_object_v<T, Args...>
1356  int>::type = 0>
1357  void push(const T & value, Args &&... args)
1358  {
1359  if constexpr(internal::has_configuration_save_object_v<T, Args...>)
1360  {
1361  push(mc_rtc::ConfigurationLoader<T>::save(value, std::forward<Args>(args)...));
1362  }
1363  else { push(value.toConfiguration(std::forward<Args>(args)...)); }
1364  }
1365 
1370  template<typename T, typename std::enable_if<internal::is_integral_v<T>, int>::type = 0>
1371  void push(const T & value)
1372  {
1373  if constexpr(internal::is_like_int8_t<T>) { push(static_cast<int8_t>(value)); }
1374  else if constexpr(internal::is_like_int16_t<T>) { push(static_cast<int16_t>(value)); }
1375  else if constexpr(internal::is_like_int32_t<T>) { push(static_cast<int32_t>(value)); }
1376  else if constexpr(internal::is_like_int64_t<T>) { push(static_cast<int64_t>(value)); }
1377  else if constexpr(internal::is_like_uint8_t<T>) { push(static_cast<uint8_t>(value)); }
1378  else if constexpr(internal::is_like_uint16_t<T>) { push(static_cast<uint16_t>(value)); }
1379  else if constexpr(internal::is_like_uint32_t<T>) { push(static_cast<uint32_t>(value)); }
1380  else if constexpr(internal::is_like_uint64_t<T>) { push(static_cast<uint64_t>(value)); }
1381  else { static_assert(!std::is_same_v<T, T>, "T is integral but has an unsupported size"); }
1382  }
1383 
1392  template<typename T, typename A = std::allocator<T>, typename... Args>
1393  void add(const std::string & key, const std::vector<T, A> & value, Args &&... args)
1394  {
1395  Configuration v = array(key, value.size());
1396  for(const auto & vi : value) { v.push(vi, std::forward<Args>(args)...); }
1397  }
1398 
1407  template<typename T, std::size_t N, typename... Args>
1408  void add(const std::string & key, const std::array<T, N> & value, Args &&... args)
1409  {
1410  Configuration v = array(key, N);
1411  for(const auto & vi : value) { v.push(vi, std::forward<Args>(args)...); }
1412  }
1413 
1422  template<typename T1, typename T2, typename... Args>
1423  void add(const std::string & key, const std::pair<T1, T2> & value, Args &&... args)
1424  {
1425  Configuration v = array(key, 2);
1426  v.push(value.first, std::forward<Args>(args)...);
1427  v.push(value.second, std::forward<Args>(args)...);
1428  }
1429 
1438  template<typename T,
1439  class C = std::less<std::string>,
1440  class A = std::allocator<std::pair<const std::string, T>>,
1441  typename... Args>
1442  void add(const std::string & key, const std::map<std::string, T, C, A> & value, Args &&... args)
1443  {
1444  Configuration v = add(key);
1445  for(const auto & el : value) { v.add(el.first, el.second, std::forward<Args>(args)...); }
1446  }
1447 
1456  template<typename T, typename C = std::less<T>, typename A = std::allocator<T>, typename... Args>
1457  void add(const std::string & key, const std::set<T, C, A> & value, Args &&... args)
1458  {
1459  Configuration v = array(key, value.size());
1460  for(const auto & v : value) { v.push(*v, std::forward<Args>(args)...); }
1461  }
1462 
1471  template<typename T,
1472  typename H = std::hash<T>,
1473  typename E = std::equal_to<T>,
1474  typename A = std::allocator<T>,
1475  typename... Args>
1476  void add(const std::string & key, const std::unordered_set<T, H, E, A> & value, Args &&... args)
1477  {
1478  Configuration v = array(key, value.size());
1479  for(const auto & v : value) { v.push(*v, std::forward<Args>(args)...); }
1480  }
1481 
1492  template<typename... Args>
1493  void add(const std::string & key, const std::variant<Args...> & value)
1494  {
1495  Configuration v = array(key, 2);
1496  v.push(value.index());
1497  std::visit([&v](const auto & hold) { v.push(hold); }, value);
1498  }
1499 
1506  template<typename T, typename std::enable_if<internal::is_integral_v<T>, int>::type = 0>
1507  void add(const std::string & key, const T & value)
1508  {
1509  if constexpr(internal::is_like_int8_t<T>) { add(key, static_cast<int8_t>(value)); }
1510  else if constexpr(internal::is_like_int16_t<T>) { add(key, static_cast<int16_t>(value)); }
1511  else if constexpr(internal::is_like_int32_t<T>) { add(key, static_cast<int32_t>(value)); }
1512  else if constexpr(internal::is_like_int64_t<T>) { add(key, static_cast<int64_t>(value)); }
1513  else if constexpr(internal::is_like_uint8_t<T>) { add(key, static_cast<uint8_t>(value)); }
1514  else if constexpr(internal::is_like_uint16_t<T>) { add(key, static_cast<uint16_t>(value)); }
1515  else if constexpr(internal::is_like_uint32_t<T>) { add(key, static_cast<uint32_t>(value)); }
1516  else if constexpr(internal::is_like_uint64_t<T>) { add(key, static_cast<uint64_t>(value)); }
1517  else { static_assert(!std::is_same_v<T, T>, "T is integral but has an unsupported size"); }
1518  }
1519 
1529  template<typename T,
1530  typename... Args,
1531  typename std::enable_if<internal::has_configuration_save_object_v<T, Args...>
1533  int>::type = 0>
1534  void add(const std::string & key, const T & value, Args &&... args)
1535  {
1536  if constexpr(internal::has_configuration_save_object_v<T, Args...>)
1537  {
1538  add(key, ConfigurationLoader<T>::save(value, std::forward<Args>(args)...));
1539  }
1540  else { add(key, value.toConfiguration(std::forward<Args>(args)...)); }
1541  }
1542 
1547  template<typename T, typename A = std::allocator<T>, typename... Args>
1548  void push(const std::vector<T, A> & value, Args &&... args)
1549  {
1550  Configuration v = array(value.size());
1551  for(const auto & vi : value) { v.push(vi, std::forward<Args>(args)...); }
1552  }
1553 
1558  template<typename T, std::size_t N, typename... Args>
1559  void push(const std::array<T, N> & value, Args &&... args)
1560  {
1561  Configuration v = array(N);
1562  for(const auto & vi : value) { v.push(vi, std::forward<Args>(args)...); }
1563  }
1564 
1569  template<typename T1, typename T2, typename... Args>
1570  void push(const std::pair<T1, T2> & value, Args &&... args)
1571  {
1572  Configuration v = array(2);
1573  v.push(value.first, std::forward<Args>(args)...);
1574  v.push(value.second, std::forward<Args>(args)...);
1575  }
1576 
1581  template<typename T,
1582  class C = std::less<std::string>,
1583  class A = std::allocator<std::pair<const std::string, T>>,
1584  typename... Args>
1585  void push(const std::map<std::string, T, C, A> & value, Args &&... args)
1586  {
1587  Configuration v = object();
1588  for(const auto & el : value) { v.add(el.first, el.second, std::forward<Args>(args)...); }
1589  }
1590 
1599  template<typename T, typename C = std::less<T>, typename A = std::allocator<T>, typename... Args>
1600  void push(const std::set<T, C, A> & value, Args &&... args)
1601  {
1602  Configuration v = array(value.size());
1603  for(const auto & v : value) { v.push(*v, std::forward<Args>(args)...); }
1604  }
1605 
1614  template<typename T,
1615  typename H = std::hash<T>,
1616  typename E = std::equal_to<T>,
1617  typename A = std::allocator<T>,
1618  typename... Args>
1619  void push(const std::unordered_set<T, H, E, A> & value, Args &&... args)
1620  {
1621  Configuration v = array(value.size());
1622  for(const auto & v : value) { v.push(*v, std::forward<Args>(args)...); }
1623  }
1624 
1635  template<typename... Args>
1636  void push(const std::variant<Args...> & value)
1637  {
1638  Configuration v = array(2);
1639  v.push(value.index());
1640  std::visit([&v](const auto & hold) { v.push(hold); }, value);
1641  }
1642 
1652  bool remove(const std::string & key);
1653 
1658  std::vector<std::string> keys() const;
1659 
1660  ConfigurationArrayIterator begin() const;
1661 
1662  ConfigurationArrayIterator end() const;
1663 
1664 private:
1665  Json v;
1666  Configuration(const Json & v);
1667 
1668  template<typename T>
1669  T convert() const
1670  {
1671  if constexpr(std::is_same_v<T, Configuration>) { return *this; }
1672  else { return this->operator T(); }
1673  }
1674 };
1675 
1677 {
1679  bool operator!=(const ConfigurationArrayIterator & rhs) const;
1680  ConfigurationArrayIterator & operator++();
1681  Configuration operator*();
1682  const Configuration operator*() const;
1683  size_t i = 0;
1685 };
1686 
1688 template<>
1689 void MC_RTC_UTILS_DLLAPI Configuration::operator()(const std::string & key, std::string & v) const;
1690 
1711 {
1713  ConfigurationFile(const std::string & path);
1714 
1716  void reload();
1717 
1719  void save() const;
1720 
1721  using Configuration::save;
1722 
1724  inline const std::string & path() const noexcept { return path_; }
1725 
1726 private:
1727  std::string path_;
1728 };
1729 
1730 #if MC_RTC_USE_VARIANT_WORKAROUND
1731 namespace internal
1732 {
1733 
1734 template<size_t IDX, typename... Args>
1735 std::variant<Args...> to_variant(const Configuration & c, size_t idx)
1736 {
1737  // Note: this never happens because we always pass idx < sizeof...(Args)
1738  if constexpr(IDX >= sizeof...(Args)) { mc_rtc::log::error_and_throw("Invalid runtime index for variant"); }
1739  else
1740  {
1741  if(idx == IDX) { return c.operator std::variant_alternative_t<IDX, std::variant<Args...>>(); }
1742  else { return to_variant<IDX + 1, Args...>(c, idx); }
1743  }
1744 }
1745 
1746 } // namespace internal
1747 #endif
1748 
1749 } // namespace mc_rtc
1750 
1752 MC_RTC_UTILS_DLLAPI std::ostream & operator<<(std::ostream & os, const mc_rtc::Configuration & c);
1753 
1754 namespace fmt
1755 {
1756 
1757 template<>
1758 struct formatter<mc_rtc::Configuration> : public formatter<string_view>
1759 {
1760  template<typename FormatContext>
1761  auto format(const mc_rtc::Configuration & c, FormatContext & ctx) -> decltype(ctx.out())
1762  {
1763  return formatter<string_view>::format(static_cast<std::string>(c), ctx);
1764  }
1765 };
1766 
1767 } // namespace fmt
mc_rtc::Configuration::add
void add(const std::string &key, const std::unordered_set< T, H, E, A > &value, Args &&... args)
Add an unordered set into the JSON document.
Definition: Configuration.h:1476
mc_rtc::Configuration
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
mc_rtc::Configuration::save
void save(const std::string &path, bool pretty=true) const
Save the configuration to a file.
mc_rtc::MessagePackBuilder
Definition: MessagePackBuilder.h:86
mc_rtc::Configuration::isArray
bool isArray() const noexcept
Returns true if the underlying value is an array.
Definition: Configuration.h:873
mc_rtc::Configuration::Exception::silence
void silence() const noexcept
mc_rtc::internal::_has_configuration_save_object::test
static std::true_type test(T *p)
mc_rtc::Configuration::operator==
bool operator==(const T &rhs) const
Compare stored values with given value.
Definition: Configuration.h:975
mc_rtc::ConfigurationArrayIterator
Definition: Configuration.h:1676
mc_rtc::Configuration::operator()
T operator()(const std::string &key, const T &v) const
Retrieve a given value stored within the configuration with a default value.
Definition: Configuration.h:951
mc_rtc::Configuration::find
std::optional< T > find(const std::string &key, Args &&... others) const
Return the Configuration entry at (key, others...) if it exists, std::nullopt otherwise.
Definition: Configuration.h:854
mc_rtc::internal::_has_toConfiguration_method
Definition: Configuration.h:135
mc_rbdyn::Gains2d
Gains< 2 > Gains2d
Definition: Gains.h:33
rpy_utils.h
mc_rtc::Configuration::add
void add(const std::string &key, const std::variant< Args... > &value)
Add a variant object into the JSON document.
Definition: Configuration.h:1493
mc_rtc::Configuration::add
void add(const std::string &key, const std::map< std::string, T, C, A > &value, Args &&... args)
Add string-indexed map into the JSON document.
Definition: Configuration.h:1442
mc_rtc::ConfigurationLoader< void >::load
static void load(const mc_rtc::Configuration &)
Definition: Configuration.h:65
mc_rtc::internal::has_configuration_save_object_v
constexpr bool has_configuration_save_object_v
Definition: Configuration.h:128
mc_rtc::Configuration::push
void push(const std::unordered_set< T, H, E, A > &value, Args &&... args)
Push an unordered set into the JSON document.
Definition: Configuration.h:1619
mc_rtc::internal::_has_configuration_save_object
Definition: Configuration.h:113
mc_rtc::Configuration::push
void push(const std::vector< T, A > &value, Args &&... args)
Push a vector into the JSON document.
Definition: Configuration.h:1548
mc_rtc::Configuration::Exception::Exception
Exception(const std::string &msg, const Configuration &c)
Constructor.
Definition: Configuration.h:239
mc_rtc::internal::has_configuration_load_object_v
constexpr bool has_configuration_load_object_v
Definition: Configuration.h:88
mc_rtc::Configuration::isObject
bool isObject() const noexcept
Returns true if the underlying value is an object.
Definition: Configuration.h:876
mc_rtc::Configuration::push
void push(const std::variant< Args... > &value)
Push a variant object into the JSON document.
Definition: Configuration.h:1636
mc_rtc::ConfigurationLoader< void >::save
static void save()
Definition: Configuration.h:66
mc_rtc::Configuration::at
T at(size_t i, const T &v) const
Retrieve a given value from a JSON array.
Definition: Configuration.h:902
fmt::formatter< mc_rtc::Configuration >::format
auto format(const mc_rtc::Configuration &c, FormatContext &ctx) -> decltype(ctx.out())
Definition: Configuration.h:1761
mc_rbdyn::Gains6d
Gains< 6 > Gains6d
Definition: Gains.h:35
Gains.h
mc_rtc::Configuration::add
void add(const std::string &key, const std::vector< T, A > &value, Args &&... args)
Add a vector into the JSON document.
Definition: Configuration.h:1393
mc_rtc::Configuration::push
void push(const std::pair< T1, T2 > &value, Args &&... args)
Push a pair into the JSON document.
Definition: Configuration.h:1570
mc_rtc::Configuration::add
void add(const std::string &key, const std::array< T, N > &value, Args &&... args)
Add an array into the JSON document.
Definition: Configuration.h:1408
mc_rtc::ConfigurationLoader::load
static void load(const mc_rtc::Configuration &)
Definition: Configuration.h:57
mc_rtc::internal::has_static_fromConfiguration_v
constexpr bool has_static_fromConfiguration_v
Definition: Configuration.h:107
mc_rtc::Configuration::add
void add(const std::string &key, const std::set< T, C, A > &value, Args &&... args)
Add a set into the JSON document.
Definition: Configuration.h:1457
mc_rtc::Configuration::push
void push(const std::array< T, N > &value, Args &&... args)
Push an array into the JSON document.
Definition: Configuration.h:1559
operator<<
MC_RTC_UTILS_DLLAPI std::ostream & operator<<(std::ostream &os, const mc_rtc::Configuration &c)
Ostream operator.
mc_rtc::Configuration::add
void add(const std::string &key, bool value)
Add a bool element to the Configuration.
mc_rtc::Configuration::add
void add(const std::string &key, const T &value, Args &&... args)
User-defined conversion.
Definition: Configuration.h:1534
mc_rtc::Configuration::add
void add(const std::string &key, const std::pair< T1, T2 > &value, Args &&... args)
Add a pair into the JSON document.
Definition: Configuration.h:1423
mc_rtc::Configuration::push
void push(const std::set< T, C, A > &value, Args &&... args)
Push a set into the JSON document.
Definition: Configuration.h:1600
mc_rtc::Configuration::isNumeric
bool isNumeric() const noexcept
Returns true if the underlying value is numeric.
Definition: Configuration.h:882
mc_rtc::log::error_and_throw
void error_and_throw(Args &&... args)
Definition: logging.h:47
mc_rtc::internal::has_toConfiguration_method_v
constexpr bool has_toConfiguration_method_v
Definition: Configuration.h:149
mc_rtc::Configuration::push
void push(const T &value, Args &&... args)
User-defined conversion.
Definition: Configuration.h:1357
mc_rtc::internal::_has_static_fromConfiguration
Definition: Configuration.h:95
mc_rtc::Configuration::Exception
Exception thrown by this class when something bad occurs.
Definition: Configuration.h:223
mc_rtc::Configuration::isString
bool isString() const noexcept
Returns true if the underlying value is a string.
Definition: Configuration.h:879
mc_rtc::internal::_has_configuration_load_object
Definition: Configuration.h:75
MessagePackBuilder.h
mc_rtc::internal::_has_configuration_load_object::test
static std::true_type test(T *p)
mc_rtc::Configuration::operator()
void operator()(const std::string &key, T &v) const
Retrieve and store a given value stored within the configuration.
Definition: Configuration.h:928
MC_RTC_UTILS_DLLAPI
#define MC_RTC_UTILS_DLLAPI
Definition: utils_api.h:50
mc_rbdyn::operator==
bool operator==(const mc_rbdyn::BodySensor &lhs, const mc_rbdyn::BodySensor &rhs)
Definition: BodySensor.h:147
mc_rtc::Configuration::add
void add(const std::string &key, const T &value)
Definition: Configuration.h:1507
deprecated.h
mc_rtc::internal::_has_toConfiguration_method::test
static std::true_type test(T *p)
mc_rtc::ConfigurationFile::path
const std::string & path() const noexcept
Definition: Configuration.h:1724
std
Definition: Contact.h:66
fmt
Definition: Configuration.h:1754
mc_rtc::ConfigurationArrayIterator::conf
Configuration conf
Definition: Configuration.h:1684
mc_rtc::Configuration::find
std::optional< Configuration > find(const std::string &key, Args &&... others) const
Return the Configuration entry at (key, others...) if it exists, std::nullopt otherwise.
Definition: Configuration.h:837
mc_rtc::Configuration::push
void push(const T &value)
Definition: Configuration.h:1371
mc_rtc::internal::_has_static_fromConfiguration::test
static std::true_type test(T *p)
mc_rtc::Configuration
struct MC_RTC_UTILS_DLLAPI Configuration
Definition: Configuration.h:46
mc_rtc::Configuration::push
void push(const std::map< std::string, T, C, A > &value, Args &&... args)
Push a string-indexed map into the JSON document.
Definition: Configuration.h:1585
mc_rtc::ConfigurationLoader::save
static void save(const T &)
Definition: Configuration.h:59
mc_rtc::Configuration::push
void push(bool value)
Insert a bool element into an array.
mc_rtc::ConfigurationFile
Configuration object that keeps track of the file it comes from
Definition: Configuration.h:1710
mc_rbdyn
Definition: generic_gripper.h:14
mc_rbdyn::Gains3d
Gains< 3 > Gains3d
Definition: Gains.h:34
mc_rtc::ConfigurationArrayIterator
struct MC_RTC_UTILS_DLLAPI ConfigurationArrayIterator
Definition: Configuration.h:45
mc_rtc::ConfigurationLoader
Definition: Configuration.h:55
mc_rtc::Configuration::operator()
Configuration operator()(const std::string &key) const
Returns a Entry value stored within the configuration.
mc_rtc
Definition: Contact.h:87