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 enum class PortDirection{
44  INPUT,
45  OUTPUT,
46  INOUT
47 };
48 
49 
50 typedef nonstd::string_view StringView;
51 
60 template <typename T> inline
61 T convertFromString(StringView /*str*/)
62 {
63  auto type_name = BT::demangle( typeid(T) );
64 
65  std::cerr << "You (maybe indirectly) called BT::convertFromString() for type [" <<
66  type_name <<"], but I can't find the template specialization.\n" << std::endl;
67 
68  throw LogicError(std::string("You didn't implement the template specialization of "
69  "convertFromString for this type: ") + type_name );
70 }
71 
72 template <>
73 std::string convertFromString<std::string>(StringView str);
74 
75 template <>
76 const char* convertFromString<const char*>(StringView str);
77 
78 template <>
79 int convertFromString<int>(StringView str);
80 
81 template <>
82 unsigned convertFromString<unsigned>(StringView str);
83 
84 template <>
85 long convertFromString<long>(StringView str);
86 
87 template <>
88 unsigned long convertFromString<unsigned long>(StringView str);
89 
90 template <>
91 float convertFromString<float>(StringView str);
92 
93 template <>
94 double convertFromString<double>(StringView str);
95 
96 template <> // Integer numbers separated by the characted ";"
97 std::vector<int> convertFromString<std::vector<int>>(StringView str);
98 
99 template <> // Real numbers separated by the characted ";"
100 std::vector<double> convertFromString<std::vector<double>>(StringView str);
101 
102 template <> // This recognizes either 0/1, true/false, TRUE/FALSE
103 bool convertFromString<bool>(StringView str);
104 
105 template <> // Names with all capital letters
107 
108 template <> // Names with all capital letters
109 NodeType convertFromString<NodeType>(StringView str);
110 
111 template <>
113 
114 
115 typedef std::function<Any(StringView)> StringConverter;
116 
117 typedef std::unordered_map<const std::type_info*, StringConverter> StringConvertersMap;
118 
119 
120 // helper function
121 template <typename T> inline
122 StringConverter GetAnyFromStringFunctor()
123 {
124  return [](StringView str){ return Any(convertFromString<T>(str)); };
125 }
126 
127 template <> inline
129 {
130  return {};
131 }
132 
133 //------------------------------------------------------------------
134 
135 template <typename T>
136 std::string toStr(T value)
137 {
138  return std::to_string(value);
139 }
140 
141 std::string toStr(std::string value);
142 
143 template<> std::string toStr<BT::NodeStatus>(BT::NodeStatus status);
144 
148 std::string toStr(BT::NodeStatus status, bool colored);
149 
150 std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status);
151 
155 template<> std::string toStr<BT::NodeType>(BT::NodeType type);
156 
157 std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
158 
159 
160 template<> std::string toStr<BT::PortDirection>(BT::PortDirection direction);
161 
162 std::ostream& operator<<(std::ostream& os, const BT::PortDirection& type);
163 
164 // Small utility, unless you want to use <boost/algorithm/string.hpp>
165 std::vector<StringView> splitString(const StringView& strToSplit, char delimeter);
166 
167 template <typename Predicate>
168 using enable_if = typename std::enable_if< Predicate::value >::type*;
169 
170 template <typename Predicate>
171 using enable_if_not = typename std::enable_if< !Predicate::value >::type*;
172 
173 
190 template <typename T> using Optional = nonstd::expected<T, std::string>;
191 // note: we use the name Optional instead of expected because it is more intuitive
192 // for users that are not up to date with "modern" C++
193 
211 
212 class PortInfo
213 {
214 
215 public:
217  _type(direction), _info(nullptr) {}
218 
220  const std::type_info& type_info,
221  StringConverter conv):
222  _type(direction),
223  _info( &type_info ),
224  _converter(conv)
225  {}
226 
227  PortDirection direction() const;
228 
229  const std::type_info* type() const;
230 
231  Any parseString(const char *str) const;
232 
233  Any parseString(const std::string& str) const;
234 
235  template <typename T>
236  Any parseString(const T& ) const
237  {
238  // avoid compilation errors
239  return {};
240  }
241 
242  void setDescription(StringView description);
243 
244  void setDefaultValue(StringView default_value_as_string);
245 
246  const std::string& description() const;
247 
248  const std::string& defaultValue() const;
249 
250 private:
251 
253  const std::type_info* _info;
254  StringConverter _converter;
255  std::string description_;
256  std::string default_value_;
257 };
258 
259 template <typename T = void>
260 std::pair<std::string,PortInfo> CreatePort(PortDirection direction,
261  StringView name,
262  StringView description = {})
263 {
264  std::pair<std::string,PortInfo> out;
265 
266  if( std::is_same<T, void>::value)
267  {
268  out = {static_cast<std::string>(name), PortInfo(direction) };
269  }
270  else{
271  out = {static_cast<std::string>(name), PortInfo(direction, typeid(T),
272  GetAnyFromStringFunctor<T>() ) };
273  }
274  if( !description.empty() )
275  {
276  out.second.setDescription(description);
277  }
278  return out;
279 }
280 
281 //----------
282 template <typename T = void> inline
283  std::pair<std::string,PortInfo> InputPort(StringView name, StringView description = {})
284 {
285  return CreatePort<T>(PortDirection::INPUT, name, description );
286 }
287 
288 template <typename T = void> inline
289 std::pair<std::string,PortInfo> OutputPort(StringView name, StringView description = {})
290 {
291  return CreatePort<T>(PortDirection::OUTPUT, name, description );
292 }
293 
294 template <typename T = void> inline
295  std::pair<std::string,PortInfo> BidirectionalPort(StringView name, StringView description = {})
296 {
297  return CreatePort<T>(PortDirection::INOUT, name, description );
298 }
299 //----------
300 template <typename T = void> inline
301  std::pair<std::string,PortInfo> InputPort(StringView name, const T& default_value, StringView description)
302 {
303  auto out = CreatePort<T>(PortDirection::INPUT, name, description );
304  out.second.setDefaultValue( BT::toStr(default_value) );
305  return out;
306 }
307 
308 template <typename T = void> inline
309  std::pair<std::string,PortInfo> BidirectionalPort(StringView name, const T& default_value, StringView description)
310 {
311  auto out = CreatePort<T>(PortDirection::INOUT, name, description );
312  out.second.setDefaultValue( BT::toStr(default_value) );
313  return out;
314 }
315 //----------
316 
317 typedef std::unordered_map<std::string, PortInfo> PortsList;
318 
319 template <typename T, typename = void>
320 struct has_static_method_providedPorts: std::false_type {};
321 
322 template <typename T>
324  typename std::enable_if<std::is_same<decltype(T::providedPorts()), PortsList>::value>::type>
325  : std::true_type {};
326 
327 template <typename T> inline
329 {
330  return T::providedPorts();
331 }
332 
333 template <typename T> inline
335 {
336  return {};
337 }
338 
339 typedef std::chrono::high_resolution_clock::time_point TimePoint;
340 typedef std::chrono::high_resolution_clock::duration Duration;
341 
342 } // end namespace
343 
344 
345 #endif // BT_BASIC_TYPES_H
NodeStatus convertFromString< NodeStatus >(StringView str)
PortDirection convertFromString< PortDirection >(StringView str)
StringConverter _converter
Definition: basic_types.h:254
float convertFromString< float >(StringView str)
const std::type_info * _info
Definition: basic_types.h:253
std::chrono::high_resolution_clock::time_point TimePoint
Definition: basic_types.h:339
Position2D convertFromString(StringView str)
std::pair< std::string, PortInfo > BidirectionalPort(StringView name, StringView description={})
Definition: basic_types.h:295
std::string toStr(T value)
Definition: basic_types.h:136
std::string default_value_
Definition: basic_types.h:256
std::string description_
Definition: basic_types.h:255
Definition: any.hpp:455
long convertFromString< long >(StringView str)
std::ostream & operator<<(std::ostream &os, const BT::NodeStatus &status)
std::pair< std::string, PortInfo > OutputPort(StringView name, StringView description={})
Definition: basic_types.h:289
Optional< void > Result
Definition: basic_types.h:210
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
std::string demangle(char const *name)
Definition: demangle_util.h:78
const char * convertFromString< const char * >(StringView str)
Any parseString(const T &) const
Definition: basic_types.h:236
StringConverter GetAnyFromStringFunctor()
Definition: basic_types.h:122
PortDirection _type
Definition: basic_types.h:252
nonstd::string_view StringView
Definition: basic_types.h:50
PortsList getProvidedPorts(enable_if< has_static_method_providedPorts< T > >=nullptr)
Definition: basic_types.h:328
unsigned convertFromString< unsigned >(StringView str)
NodeType convertFromString< NodeType >(StringView str)
bool convertFromString< bool >(StringView str)
typename std::enable_if< Predicate::value >::type * enable_if
Definition: basic_types.h:168
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:317
StringConverter GetAnyFromStringFunctor< void >()
Definition: basic_types.h:128
std::pair< std::string, PortInfo > CreatePort(PortDirection direction, StringView name, StringView description={})
Definition: basic_types.h:260
nonstd::expected< T, std::string > Optional
Definition: basic_types.h:190
int convertFromString< int >(StringView str)
std::function< Any(StringView)> StringConverter
Definition: basic_types.h:115
typename std::enable_if< !Predicate::value >::type * enable_if_not
Definition: basic_types.h:171
PortInfo(PortDirection direction, const std::type_info &type_info, StringConverter conv)
Definition: basic_types.h:219
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:117
std::basic_string< CharT, Traits > to_string(basic_string_view< CharT, Traits > v)
PortDirection
Definition: basic_types.h:43
std::pair< std::string, PortInfo > InputPort(StringView name, StringView description={})
Definition: basic_types.h:283
std::chrono::high_resolution_clock::duration Duration
Definition: basic_types.h:340
double convertFromString< double >(StringView str)
unsigned long convertFromString< unsigned long >(StringView str)
PortInfo(PortDirection direction=PortDirection::INOUT)
Definition: basic_types.h:216


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:24