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 double convertFromString<double>(StringView str);
86 
87 template <> // Integer numbers separated by the characted ";"
88 std::vector<int> convertFromString<std::vector<int>>(StringView str);
89 
90 template <> // Real numbers separated by the characted ";"
91 std::vector<double> convertFromString<std::vector<double>>(StringView str);
92 
93 template <> // This recognizes either 0/1, true/false, TRUE/FALSE
94 bool convertFromString<bool>(StringView str);
95 
96 template <> // Names with all capital letters
98 
99 template <> // Names with all capital letters
101 
102 template <>
104 
105 
106 typedef std::function<Any(StringView)> StringConverter;
107 
108 typedef std::unordered_map<const std::type_info*, StringConverter> StringConvertersMap;
109 
110 
111 // helper function
112 template <typename T> inline
113 StringConverter GetAnyFromStringFunctor()
114 {
115  return [](StringView str){ return Any(convertFromString<T>(str)); };
116 }
117 
118 template <> inline
120 {
121  return {};
122 }
123 
124 //------------------------------------------------------------------
125 
126 template <typename T>
127 std::string toStr(T value)
128 {
129  return std::to_string(value);
130 }
131 
132 std::string toStr(std::string value);
133 
134 template<> std::string toStr<BT::NodeStatus>(BT::NodeStatus status);
135 
139 std::string toStr(BT::NodeStatus status, bool colored);
140 
141 std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status);
142 
146 template<> std::string toStr<BT::NodeType>(BT::NodeType type);
147 
148 std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
149 
150 
151 template<> std::string toStr<BT::PortDirection>(BT::PortDirection direction);
152 
153 std::ostream& operator<<(std::ostream& os, const BT::PortDirection& type);
154 
155 // Small utility, unless you want to use <boost/algorithm/string.hpp>
156 std::vector<StringView> splitString(const StringView& strToSplit, char delimeter);
157 
158 template <typename Predicate>
159 using enable_if = typename std::enable_if< Predicate::value >::type*;
160 
161 template <typename Predicate>
162 using enable_if_not = typename std::enable_if< !Predicate::value >::type*;
163 
164 
181 template <typename T> using Optional = nonstd::expected<T, std::string>;
182 // note: we use the name Optional instead of expected because it is more intuitive
183 // for users that are not up to date with "modern" C++
184 
202 
203 class PortInfo
204 {
205 
206 public:
208  _type(direction), _info(nullptr) {}
209 
211  const std::type_info& type_info,
212  StringConverter conv):
213  _type(direction),
214  _info( &type_info ),
215  _converter(conv)
216  {}
217 
218  PortDirection direction() const;
219 
220  const std::type_info* type() const;
221 
222  Any parseString(const char *str) const;
223 
224  Any parseString(const std::string& str) const;
225 
226  template <typename T>
227  Any parseString(const T& ) const
228  {
229  // avoid compilation errors
230  return {};
231  }
232 
233  void setDescription(StringView description);
234 
235  void setDefaultValue(StringView default_value_as_string);
236 
237  const std::string& description() const;
238 
239  const std::string& defaultValue() const;
240 
241 private:
242 
244  const std::type_info* _info;
245  StringConverter _converter;
246  std::string description_;
247  std::string default_value_;
248 };
249 
250 template <typename T = void>
251 std::pair<std::string,PortInfo> CreatePort(PortDirection direction,
252  StringView name,
253  StringView description = {})
254 {
255  std::pair<std::string,PortInfo> out;
256 
257  if( std::is_same<T, void>::value)
258  {
259  out = {name.to_string(), PortInfo(direction) };
260  }
261  else{
262  out = {name.to_string(), PortInfo(direction, typeid(T),
263  GetAnyFromStringFunctor<T>() ) };
264  }
265  if( !description.empty() )
266  {
267  out.second.setDescription(description);
268  }
269  return out;
270 }
271 
272 //----------
273 template <typename T = void> inline
274  std::pair<std::string,PortInfo> InputPort(StringView name, StringView description = {})
275 {
276  return CreatePort<T>(PortDirection::INPUT, name, description );
277 }
278 
279 template <typename T = void> inline
280 std::pair<std::string,PortInfo> OutputPort(StringView name, StringView description = {})
281 {
282  return CreatePort<T>(PortDirection::OUTPUT, name, description );
283 }
284 
285 template <typename T = void> inline
286  std::pair<std::string,PortInfo> BidirectionalPort(StringView name, StringView description = {})
287 {
288  return CreatePort<T>(PortDirection::INOUT, name, description );
289 }
290 //----------
291 template <typename T = void> inline
292  std::pair<std::string,PortInfo> InputPort(StringView name, const T& default_value, StringView description)
293 {
294  auto out = CreatePort<T>(PortDirection::INPUT, name, description );
295  out.second.setDefaultValue( BT::toStr(default_value) );
296  return out;
297 }
298 
299 template <typename T = void> inline
300  std::pair<std::string,PortInfo> OutputPort(StringView name, const T& default_value, StringView description)
301 {
302  auto out = CreatePort<T>(PortDirection::OUTPUT, name, description );
303  out.second.setDefaultValue( BT::toStr(default_value) );
304  return out;
305 }
306 
307 template <typename T = void> inline
308  std::pair<std::string,PortInfo> BidirectionalPort(StringView name, const T& default_value, StringView description)
309 {
310  auto out = CreatePort<T>(PortDirection::INOUT, name, description );
311  out.second.setDefaultValue( BT::toStr(default_value) );
312  return out;
313 }
314 //----------
315 
316 typedef std::unordered_map<std::string, PortInfo> PortsList;
317 
318 template <typename T, typename = void>
319 struct has_static_method_providedPorts: std::false_type {};
320 
321 template <typename T>
323  typename std::enable_if<std::is_same<decltype(T::providedPorts()), PortsList>::value>::type>
324  : std::true_type {};
325 
326 template <typename T> inline
328 {
329  return T::providedPorts();
330 }
331 
332 template <typename T> inline
334 {
335  return {};
336 }
337 
338 typedef std::chrono::high_resolution_clock::time_point TimePoint;
339 typedef std::chrono::high_resolution_clock::duration Duration;
340 
341 } // end namespace
342 
343 
344 #endif // BT_BASIC_TYPES_H
NodeStatus convertFromString< NodeStatus >(StringView str)
PortDirection convertFromString< PortDirection >(StringView str)
StringConverter _converter
Definition: basic_types.h:245
const std::type_info * _info
Definition: basic_types.h:244
std::chrono::high_resolution_clock::time_point TimePoint
Definition: basic_types.h:338
Position2D convertFromString(StringView str)
std::pair< std::string, PortInfo > BidirectionalPort(StringView name, StringView description={})
Definition: basic_types.h:286
std::string toStr(T value)
Definition: basic_types.h:127
std::string default_value_
Definition: basic_types.h:247
std::string description_
Definition: basic_types.h:246
Definition: any.hpp:455
std::ostream & operator<<(std::ostream &os, const BT::NodeStatus &status)
std::pair< std::string, PortInfo > OutputPort(StringView name, StringView description={})
Definition: basic_types.h:280
Optional< void > Result
Definition: basic_types.h:201
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
std::string demangle(char const *name)
Definition: demangle_util.h:78
Any parseString(const T &) const
Definition: basic_types.h:227
StringConverter GetAnyFromStringFunctor()
Definition: basic_types.h:113
PortDirection _type
Definition: basic_types.h:243
nonstd::string_view StringView
Definition: basic_types.h:50
PortsList getProvidedPorts(enable_if< has_static_method_providedPorts< T > >=nullptr)
Definition: basic_types.h:327
unsigned convertFromString< unsigned >(StringView str)
const char * str
Definition: util.h:257
NodeType convertFromString< NodeType >(StringView str)
bool convertFromString< bool >(StringView str)
const char * convertFromString< const char * >(StringView str)
typename std::enable_if< Predicate::value >::type * enable_if
Definition: basic_types.h:159
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:316
StringConverter GetAnyFromStringFunctor< void >()
Definition: basic_types.h:119
std::pair< std::string, PortInfo > CreatePort(PortDirection direction, StringView name, StringView description={})
Definition: basic_types.h:251
nonstd::expected< T, std::string > Optional
Definition: basic_types.h:181
int convertFromString< int >(StringView str)
std::function< Any(StringView)> StringConverter
Definition: basic_types.h:106
typename std::enable_if< !Predicate::value >::type * enable_if_not
Definition: basic_types.h:162
PortInfo(PortDirection direction, const std::type_info &type_info, StringConverter conv)
Definition: basic_types.h:210
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:108
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:274
std::chrono::high_resolution_clock::duration Duration
Definition: basic_types.h:339
double convertFromString< double >(StringView str)
PortInfo(PortDirection direction=PortDirection::INOUT)
Definition: basic_types.h:207


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Jun 8 2019 18:04:04