@@ -130,15 +130,21 @@ NodeType convertFromString<NodeType>(StringView str);
130
130
template <> [[nodiscard]]
131
131
PortDirection convertFromString<PortDirection>(StringView str);
132
132
133
- typedef std::function<Any(StringView)> StringConverter ;
133
+ using StringConverter = std::function<Any(StringView)>;
134
134
135
- typedef std::unordered_map<const std::type_info*, StringConverter> StringConvertersMap ;
135
+ using StringConvertersMap = std::unordered_map<const std::type_info*, StringConverter>;
136
136
137
137
// helper function
138
138
template <typename T> [[nodiscard]]
139
139
inline StringConverter GetAnyFromStringFunctor ()
140
140
{
141
- return [](StringView str) { return Any (convertFromString<T>(str)); };
141
+ if constexpr (std::is_constructible_v<StringView, T>)
142
+ {
143
+ return [](StringView str) { return Any (str); };
144
+ }
145
+ else {
146
+ return [](StringView str) { return Any (convertFromString<T>(str)); };
147
+ }
142
148
}
143
149
144
150
template <> [[nodiscard]]
@@ -152,10 +158,17 @@ inline StringConverter GetAnyFromStringFunctor<void>()
152
158
template <typename T> [[nodiscard]]
153
159
std::string toStr (const T& value)
154
160
{
155
- static_assert (std::is_arithmetic_v<T>,
156
- " You need a template specialization of BT::toStr() and "
157
- " it must be consistent with the implementation of BT::convertFromString" );
158
- return std::to_string (value);
161
+ if constexpr (!std::is_arithmetic_v<T>)
162
+ {
163
+ throw LogicError (
164
+ StrCat (" Function BT::toStr<T>() not specialized for type [" ,
165
+ BT::demangle (typeid (T)), " ]," ,
166
+ " Implement it consistently with BT::convertFromString<T>(), "
167
+ " or provide at dummy version that returns an empty string." )
168
+ );
169
+ } else {
170
+ return std::to_string (value);
171
+ }
159
172
}
160
173
161
174
template <> [[nodiscard]]
@@ -250,11 +263,11 @@ class PortInfo
250
263
};
251
264
252
265
PortInfo (PortDirection direction = PortDirection::INOUT) :
253
- _type (direction), _type_info (typeid (AnyTypeAllowed))
266
+ type_ (direction), type_info_ (typeid (AnyTypeAllowed))
254
267
{}
255
268
256
269
PortInfo (PortDirection direction, std::type_index type_info, StringConverter conv) :
257
- _type (direction), _type_info (type_info), _converter (conv)
270
+ type_ (direction), type_info_ (type_info), converter_ (conv)
258
271
{}
259
272
260
273
[[nodiscard]] PortDirection direction () const ;
@@ -274,28 +287,38 @@ class PortInfo
274
287
275
288
void setDescription (StringView description);
276
289
277
- void setDefaultValue (StringView default_value_as_string);
290
+ template <typename T>
291
+ void setDefaultValue (const T& default_value) {
292
+ default_value_ = Any (default_value);
293
+ try {
294
+ default_value_str_ = BT::toStr (default_value);
295
+ }
296
+ catch (LogicError&) {}
297
+ }
278
298
279
299
[[nodiscard]] const std::string& description () const ;
280
300
281
- [[nodiscard]] std::optional<std::string> defaultValue () const ;
301
+ [[nodiscard]] const Any& defaultValue () const ;
302
+
303
+ [[nodiscard]] const std::string& defaultValueString () const ;
282
304
283
305
[[nodiscard]] bool isStronglyTyped () const
284
306
{
285
- return _type_info != typeid (AnyTypeAllowed);
307
+ return type_info_ != typeid (AnyTypeAllowed);
286
308
}
287
309
288
310
[[nodiscard]] const StringConverter& converter () const
289
311
{
290
- return _converter ;
312
+ return converter_ ;
291
313
}
292
314
293
315
private:
294
- PortDirection _type ;
295
- std::type_index _type_info ;
296
- StringConverter _converter ;
316
+ PortDirection type_ ;
317
+ std::type_index type_info_ ;
318
+ StringConverter converter_ ;
297
319
std::string description_;
298
- std::optional<std::string> default_value_;
320
+ Any default_value_;
321
+ std::string default_value_str_;
299
322
};
300
323
301
324
template <typename T = PortInfo::AnyTypeAllowed> [[nodiscard]]
@@ -355,7 +378,7 @@ inline std::pair<std::string, PortInfo> InputPort(StringView name, const T& defa
355
378
StringView description)
356
379
{
357
380
auto out = CreatePort<T>(PortDirection::INPUT, name, description);
358
- out.second .setDefaultValue (BT::toStr ( default_value) );
381
+ out.second .setDefaultValue (default_value);
359
382
return out;
360
383
}
361
384
@@ -365,12 +388,12 @@ inline std::pair<std::string, PortInfo> BidirectionalPort(StringView name,
365
388
StringView description)
366
389
{
367
390
auto out = CreatePort<T>(PortDirection::INOUT, name, description);
368
- out.second .setDefaultValue (BT::toStr ( default_value) );
391
+ out.second .setDefaultValue (default_value);
369
392
return out;
370
393
}
371
394
// ----------
372
395
373
- typedef std::unordered_map<std::string, PortInfo> PortsList ;
396
+ using PortsList = std::unordered_map<std::string, PortInfo>;
374
397
375
398
template <typename T, typename = void >
376
399
struct has_static_method_providedPorts : std::false_type
@@ -398,8 +421,8 @@ inline PortsList
398
421
return {};
399
422
}
400
423
401
- typedef std::chrono::high_resolution_clock::time_point TimePoint ;
402
- typedef std::chrono::high_resolution_clock::duration Duration ;
424
+ using TimePoint = std::chrono::high_resolution_clock::time_point;
425
+ using Duration = std::chrono::high_resolution_clock::duration;
403
426
404
427
} // namespace BT
405
428
0 commit comments