basic_types.h
Go to the documentation of this file.
1 #ifndef BT_BASIC_TYPES_H
2 #define BT_BASIC_TYPES_H
3 
4 #include <iostream>
5 #include <vector>
6 #include <sstream>
7 #include <unordered_map>
8 #include <unordered_set>
9 #include <typeinfo>
10 #include <functional>
11 #include <chrono>
12 #include <memory>
18 
19 namespace BT
20 {
22 enum class NodeType
23 {
24  UNDEFINED = 0,
25  ACTION,
26  CONDITION,
27  CONTROL,
28  DECORATOR,
29  SUBTREE
30 };
31 
35 enum class NodeStatus
36 {
37  IDLE = 0,
38  RUNNING,
39  SUCCESS,
40  FAILURE
41 };
42 
43 inline bool StatusCompleted(const NodeStatus& status)
44 {
45  return status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE;
46 }
47 
48 enum class PortDirection
49 {
50  INPUT,
51  OUTPUT,
52  INOUT
53 };
54 
55 typedef nonstd::string_view StringView;
56 
65 template <typename T>
66 inline T convertFromString(StringView /*str*/)
67 {
68  auto type_name = BT::demangle(typeid(T));
69 
70  std::cerr << "You (maybe indirectly) called BT::convertFromString() for type ["
71  << type_name << "], but I can't find the template specialization.\n"
72  << std::endl;
73 
74  throw LogicError(std::string("You didn't implement the template specialization of "
75  "convertFromString for this type: ") +
76  type_name);
77 }
78 
79 template <>
80 std::string convertFromString<std::string>(StringView str);
81 
82 template <>
83 const char* convertFromString<const char*>(StringView str);
84 
85 template <>
86 int convertFromString<int>(StringView str);
87 
88 template <>
89 unsigned convertFromString<unsigned>(StringView str);
90 
91 template <>
92 long convertFromString<long>(StringView str);
93 
94 template <>
95 unsigned long convertFromString<unsigned long>(StringView str);
96 
97 template <>
98 float convertFromString<float>(StringView str);
99 
100 template <>
101 double convertFromString<double>(StringView str);
102 
103 template <> // Integer numbers separated by the characted ";"
104 std::vector<int> convertFromString<std::vector<int>>(StringView str);
105 
106 template <> // Real numbers separated by the characted ";"
107 std::vector<double> convertFromString<std::vector<double>>(StringView str);
108 
109 template <> // This recognizes either 0/1, true/false, TRUE/FALSE
110 bool convertFromString<bool>(StringView str);
111 
112 template <> // Names with all capital letters
114 
115 template <> // Names with all capital letters
116 NodeType convertFromString<NodeType>(StringView str);
117 
118 template <>
120 
121 typedef std::function<Any(StringView)> StringConverter;
122 
123 typedef std::unordered_map<const std::type_info*, StringConverter> StringConvertersMap;
124 
125 // helper function
126 template <typename T>
127 inline StringConverter GetAnyFromStringFunctor()
128 {
129  return [](StringView str) { return Any(convertFromString<T>(str)); };
130 }
131 
132 template <>
133 inline StringConverter GetAnyFromStringFunctor<void>()
134 {
135  return {};
136 }
137 
138 //------------------------------------------------------------------
139 
140 template <typename T>
141 std::string toStr(T value)
142 {
143  return std::to_string(value);
144 }
145 
146 std::string toStr(std::string value);
147 
148 template <>
149 std::string toStr<BT::NodeStatus>(BT::NodeStatus status);
150 
154 std::string toStr(BT::NodeStatus status, bool colored);
155 
156 std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status);
157 
161 template <>
162 std::string toStr<BT::NodeType>(BT::NodeType type);
163 
164 std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
165 
166 template <>
167 std::string toStr<BT::PortDirection>(BT::PortDirection direction);
168 
169 std::ostream& operator<<(std::ostream& os, const BT::PortDirection& type);
170 
171 // Small utility, unless you want to use <boost/algorithm/string.hpp>
172 std::vector<StringView> splitString(const StringView& strToSplit, char delimeter);
173 
174 template <typename Predicate>
175 using enable_if = typename std::enable_if<Predicate::value>::type*;
176 
177 template <typename Predicate>
178 using enable_if_not = typename std::enable_if<!Predicate::value>::type*;
179 
196 template <typename T>
197 using Optional = nonstd::expected<T, std::string>;
198 // note: we use the name Optional instead of expected because it is more intuitive
199 // for users that are not up to date with "modern" C++
200 
218 
219 const std::unordered_set<std::string> ReservedPortNames = {"ID", "name", "_description"};
220 
221 class PortInfo
222 {
223 public:
225  _type(direction), _info(nullptr)
226  {}
227 
228  PortInfo(PortDirection direction, const std::type_info& type_info,
229  StringConverter conv) :
230  _type(direction), _info(&type_info), _converter(conv)
231  {}
232 
233  PortDirection direction() const;
234 
235  const std::type_info* type() const;
236 
237  Any parseString(const char* str) const;
238 
239  Any parseString(const std::string& str) const;
240 
241  template <typename T>
242  Any parseString(const T&) const
243  {
244  // avoid compilation errors
245  return {};
246  }
247 
248  void setDescription(StringView description);
249 
250  void setDefaultValue(StringView default_value_as_string);
251 
252  const std::string& description() const;
253 
254  const std::string& defaultValue() const;
255 
256 private:
258  const std::type_info* _info;
259  StringConverter _converter;
260  std::string description_;
261  std::string default_value_;
262 };
263 
264 template <typename T = void>
265 std::pair<std::string, PortInfo> CreatePort(PortDirection direction, StringView name,
266  StringView description = {})
267 {
268  auto sname = static_cast<std::string>(name);
269  if (ReservedPortNames.count(sname) != 0)
270  {
271  throw std::runtime_error("A port can not use a reserved name. See ReservedPortNames");
272  }
273 
274  std::pair<std::string, PortInfo> out;
275 
276  if (std::is_same<T, void>::value)
277  {
278  out = {sname, PortInfo(direction)};
279  }
280  else
281  {
282  out = {sname, PortInfo(direction, typeid(T), GetAnyFromStringFunctor<T>())};
283  }
284  if (!description.empty())
285  {
286  out.second.setDescription(description);
287  }
288  return out;
289 }
290 
291 //----------
292 template <typename T = void>
293 inline std::pair<std::string, PortInfo> InputPort(StringView name,
294  StringView description = {})
295 {
296  return CreatePort<T>(PortDirection::INPUT, name, description);
297 }
298 
299 template <typename T = void>
300 inline std::pair<std::string, PortInfo> OutputPort(StringView name,
301  StringView description = {})
302 {
303  return CreatePort<T>(PortDirection::OUTPUT, name, description);
304 }
305 
306 template <typename T = void>
307 inline std::pair<std::string, PortInfo> BidirectionalPort(StringView name,
308  StringView description = {})
309 {
310  return CreatePort<T>(PortDirection::INOUT, name, description);
311 }
312 //----------
313 template <typename T = void>
314 inline std::pair<std::string, PortInfo> InputPort(StringView name, const T& default_value,
315  StringView description)
316 {
317  auto out = CreatePort<T>(PortDirection::INPUT, name, description);
318  out.second.setDefaultValue(BT::toStr(default_value));
319  return out;
320 }
321 
322 template <typename T = void>
323 inline std::pair<std::string, PortInfo> BidirectionalPort(StringView name,
324  const T& default_value,
325  StringView description)
326 {
327  auto out = CreatePort<T>(PortDirection::INOUT, name, description);
328  out.second.setDefaultValue(BT::toStr(default_value));
329  return out;
330 }
331 //----------
332 
333 typedef std::unordered_map<std::string, PortInfo> PortsList;
334 
335 template <typename T, typename = void>
336 struct has_static_method_providedPorts : std::false_type
337 {
338 };
339 
340 template <typename T>
342  T, typename std::enable_if<
343  std::is_same<decltype(T::providedPorts()), PortsList>::value>::type>
344  : std::true_type
345 {
346 };
347 
348 template <typename T>
350 {
351  return T::providedPorts();
352 }
353 
354 template <typename T>
355 inline PortsList
357 {
358  return {};
359 }
360 
361 typedef std::chrono::high_resolution_clock::time_point TimePoint;
362 typedef std::chrono::high_resolution_clock::duration Duration;
363 
364 } // namespace BT
365 
366 #endif // BT_BASIC_TYPES_H
typename std::enable_if< Predicate::value >::type * enable_if
Definition: basic_types.h:175
NodeStatus convertFromString< NodeStatus >(StringView str)
PortDirection convertFromString< PortDirection >(StringView str)
std::pair< std::string, PortInfo > InputPort(StringView name, StringView description={})
Definition: basic_types.h:293
StringConverter _converter
Definition: basic_types.h:259
float convertFromString< float >(StringView str)
const std::type_info * _info
Definition: basic_types.h:258
std::chrono::high_resolution_clock::time_point TimePoint
Definition: basic_types.h:361
std::pair< std::string, PortInfo > BidirectionalPort(StringView name, StringView description={})
Definition: basic_types.h:307
std::string toStr(T value)
Definition: basic_types.h:141
std::string default_value_
Definition: basic_types.h:261
std::string description_
Definition: basic_types.h:260
Any parseString(const T &) const
Definition: basic_types.h:242
Definition: any.hpp:455
long convertFromString< long >(StringView str)
bool StatusCompleted(const NodeStatus &status)
Definition: basic_types.h:43
std::ostream & operator<<(std::ostream &os, const BT::NodeStatus &status)
const std::unordered_set< std::string > ReservedPortNames
Definition: basic_types.h:219
Optional< void > Result
Definition: basic_types.h:217
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
std::string demangle(char const *name)
Definition: demangle_util.h:72
StringConverter GetAnyFromStringFunctor()
Definition: basic_types.h:127
PortDirection _type
Definition: basic_types.h:257
nonstd::string_view StringView
Definition: basic_types.h:55
unsigned convertFromString< unsigned >(StringView str)
NodeType convertFromString< NodeType >(StringView str)
bool convertFromString< bool >(StringView str)
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:333
std::pair< std::string, PortInfo > OutputPort(StringView name, StringView description={})
Definition: basic_types.h:300
StringConverter GetAnyFromStringFunctor< void >()
Definition: basic_types.h:133
nonstd::expected< T, std::string > Optional
Definition: basic_types.h:197
int convertFromString< int >(StringView str)
std::function< Any(StringView)> StringConverter
Definition: basic_types.h:121
PortInfo(PortDirection direction, const std::type_info &type_info, StringConverter conv)
Definition: basic_types.h:228
NodeStatus
Definition: basic_types.h:35
void setDescription(StringView description)
NodeType
Enumerates the possible types of nodes.
Definition: basic_types.h:22
std::unordered_map< const std::type_info *, StringConverter > StringConvertersMap
Definition: basic_types.h:123
std::basic_string< CharT, Traits > to_string(basic_string_view< CharT, Traits > v)
PortDirection
Definition: basic_types.h:48
PortsList getProvidedPorts(enable_if< has_static_method_providedPorts< T >>=nullptr)
Definition: basic_types.h:349
std::chrono::high_resolution_clock::duration Duration
Definition: basic_types.h:362
std::pair< std::string, PortInfo > CreatePort(PortDirection direction, StringView name, StringView description={})
Definition: basic_types.h:265
double convertFromString< double >(StringView str)
unsigned long convertFromString< unsigned long >(StringView str)
typename std::enable_if<!Predicate::value >::type * enable_if_not
Definition: basic_types.h:178
Point3D convertFromString(StringView key)
PortInfo(PortDirection direction=PortDirection::INOUT)
Definition: basic_types.h:224


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:14