ddynamic_reconfigure_utils.h
Go to the documentation of this file.
1 
30 #ifndef DDYNAMIC_RECONFIGURE_UTILS_H
31 #define DDYNAMIC_RECONFIGURE_UTILS_H
32 #include <string>
33 #include <limits>
34 #include <vector>
35 
36 template <typename T>
37 inline T getMin()
38 {
39  return std::numeric_limits<T>::min();
40 }
41 
42 template <>
43 inline bool getMin()
44 {
45  return false;
46 }
47 
48 template <>
49 inline std::string getMin<std::string>()
50 {
51  return "";
52 }
53 
54 template <typename T>
55 inline T getMax()
56 {
57  return std::numeric_limits<T>::max();
58 }
59 
60 template <>
61 inline bool getMax()
62 {
63  return true;
64 }
65 
66 template <>
67 inline std::string getMax()
68 {
69  return "";
70 }
71 
72 
73 template <class T, class V>
74 bool assignValue(const std::vector<T> &v, const std::string &name, const V &value)
75 {
76  for (unsigned int i = 0; i < v.size(); ++i)
77  {
78  if (v[i]->name_ == name)
79  {
80  v[i]->updateValue(value);
81  return true;
82  }
83  }
84  return false;
85 }
86 
87 template <typename T>
88 void attemptGetParam(ros::NodeHandle &nh, const std::string &name, T &param, T default_value)
89 {
90  if (nh.hasParam(name))
91  {
92  nh.param<T>(name, param, default_value);
93  }
94 }
95 template <typename T>
96 std::pair<T, T> getMinMax(const std::map<std::string, T> &enum_map)
97 {
98  T min, max;
99  if (enum_map.empty())
100  {
101  throw std::runtime_error("Trying to register an empty enum");
102  }
103 
104  min = enum_map.begin()->second;
105  max = enum_map.begin()->second;
106 
107  for (const auto &it : enum_map)
108  {
109  min = std::min(min, it.second);
110  max = std::max(min, it.second);
111  }
112 
113  return std::make_pair(min, max);
114 }
115 
116 
117 
118 #endif // DDYNAMIC_RECONFIGURE_UTILS_H
void attemptGetParam(ros::NodeHandle &nh, const std::string &name, T &param, T default_value)
std::pair< T, T > getMinMax(const std::map< std::string, T > &enum_map)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool assignValue(const std::vector< T > &v, const std::string &name, const V &value)
bool hasParam(const std::string &key) const
int min(int a, int b)


ddynamic_reconfigure
Author(s): Hilario Tome
autogenerated on Mon Feb 28 2022 22:12:28