• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

BehaviorTree / BehaviorTree.CPP / 21666306232

04 Feb 2026 09:38AM UTC coverage: 77.963% (+0.6%) from 77.406%
21666306232

Pull #1104

github

web-flow
Merge 654adab19 into 061fd8ea3
Pull Request #1104: Fix #953: getInput() now uses stored converter for plugin custom types

10 of 10 new or added lines in 1 file covered. (100.0%)

2 existing lines in 1 file now uncovered.

4256 of 5459 relevant lines covered (77.96%)

24212.6 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

94.25
/include/behaviortree_cpp/basic_types.h
1
#pragma once
2

3
#include "behaviortree_cpp/contrib/expected.hpp"
4
#include "behaviortree_cpp/exceptions.h"
5
#include "behaviortree_cpp/utils/safe_any.hpp"
6

7
#include <chrono>
8
#include <functional>
9
#include <iostream>
10
#include <string_view>
11
#include <typeinfo>
12
#include <unordered_map>
13
#include <utility>
14
#include <variant>
15
#include <vector>
16

17
namespace BT
18
{
19
/// Enumerates the possible types of nodes
20
enum class NodeType
21
{
22
  UNDEFINED = 0,
23
  ACTION,
24
  CONDITION,
25
  CONTROL,
26
  DECORATOR,
27
  SUBTREE
28
};
29

30
/// Enumerates the states every node can be in after execution during a particular
31
/// time step.
32
/// IMPORTANT: Your custom nodes should NEVER return IDLE.
33
enum class NodeStatus
34
{
35
  IDLE = 0,
36
  RUNNING = 1,
37
  SUCCESS = 2,
38
  FAILURE = 3,
39
  SKIPPED = 4,
40
};
41

42
inline bool isStatusActive(const NodeStatus& status)
1,416✔
43
{
44
  return status != NodeStatus::IDLE && status != NodeStatus::SKIPPED;
1,416✔
45
}
46

47
inline bool isStatusCompleted(const NodeStatus& status)
608,308✔
48
{
49
  return status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE;
608,308✔
50
}
51

52
enum class PortDirection
53
{
54
  INPUT,
55
  OUTPUT,
56
  INOUT
57
};
58

59
using StringView = std::string_view;
60

61
bool StartWith(StringView str, StringView prefix);
62

63
bool StartWith(StringView str, char prefix);
64

65
// vector of key/value pairs
66
using KeyValueVector = std::vector<std::pair<std::string, std::string>>;
67

68
/** Usage: given a function/method like this:
69
 *
70
 *     Expected<double> getAnswer();
71
 *
72
 * User code can check result and error message like this:
73
 *
74
 *     auto res = getAnswer();
75
 *     if( res )
76
 *     {
77
 *         std::cout << "answer was: " << res.value() << std::endl;
78
 *     }
79
 *     else{
80
 *         std::cerr << "failed to get the answer: " << res.error() << std::endl;
81
 *     }
82
 *
83
 * */
84
template <typename T>
85
using Expected = nonstd::expected<T, std::string>;
86

87
struct AnyTypeAllowed
88
{
89
};
90

91
/**
92
 * @brief convertFromJSON will parse a json string and use JsonExporter
93
 * to convert its content to a given type. It will work only if
94
 * the type was previously registered. May throw if it fails.
95
 *
96
 * @param json_text a valid JSON string
97
 * @param type you must specify the typeid()
98
 * @return the object, wrapped in Any.
99
 */
100
[[nodiscard]] Any convertFromJSON(StringView json_text, std::type_index type);
101

102
/// Same as the non template version, but with automatic casting
103
template <typename T>
104
[[nodiscard]] inline T convertFromJSON(StringView str)
2✔
105
{
106
  return convertFromJSON(str, typeid(T)).cast<T>();
2✔
107
}
108

109
/**
110
 * convertFromString is used to convert a string into a custom type.
111
 *
112
 * This function is invoked under the hood by TreeNode::getInput(), but only when the
113
 * input port contains a string.
114
 *
115
 * If you have a custom type, you need to implement the corresponding
116
 * template specialization.
117
 *
118
 * If the string starts with the prefix "json:", it will
119
 * fall back to convertFromJSON()
120
 */
121
template <typename T>
122
[[nodiscard]] inline T convertFromString(StringView str)
2✔
123
{
124
  // if string starts with "json:{", try to parse it as json
125
  if(StartWith(str, "json:"))
2✔
126
  {
127
    str.remove_prefix(5);
1✔
128
    return convertFromJSON<T>(str);
2✔
129
  }
130

131
  auto type_name = BT::demangle(typeid(T));
1✔
132

133
  std::cerr << "You (maybe indirectly) called BT::convertFromString() for type ["
134
            << type_name << "], but I can't find the template specialization.\n"
1✔
135
            << std::endl;
1✔
136

137
  throw LogicError(std::string("You didn't implement the template specialization of "
3✔
138
                               "convertFromString for this type: ") +
139
                   type_name);
140
}
1✔
141

142
template <>
143
[[nodiscard]] std::string convertFromString<std::string>(StringView str);
144

145
template <>
146
[[nodiscard]] const char* convertFromString<const char*>(StringView str);
147

148
template <>
149
[[nodiscard]] int8_t convertFromString<int8_t>(StringView str);
150

151
template <>
152
[[nodiscard]] int16_t convertFromString<int16_t>(StringView str);
153

154
template <>
155
[[nodiscard]] int32_t convertFromString<int32_t>(StringView str);
156

157
template <>
158
[[nodiscard]] int64_t convertFromString<int64_t>(StringView str);
159

160
template <>
161
[[nodiscard]] uint8_t convertFromString<uint8_t>(StringView str);
162

163
template <>
164
[[nodiscard]] uint16_t convertFromString<uint16_t>(StringView str);
165

166
template <>
167
[[nodiscard]] uint32_t convertFromString<uint32_t>(StringView str);
168

169
template <>
170
[[nodiscard]] uint64_t convertFromString<uint64_t>(StringView str);
171

172
template <>
173
[[nodiscard]] float convertFromString<float>(StringView str);
174

175
template <>
176
[[nodiscard]] double convertFromString<double>(StringView str);
177

178
// Integer numbers separated by the character ";"
179
template <>
180
[[nodiscard]] std::vector<int> convertFromString<std::vector<int>>(StringView str);
181

182
// Real numbers separated by the character ";"
183
template <>
184
[[nodiscard]] std::vector<double> convertFromString<std::vector<double>>(StringView str);
185

186
// Boolean values separated by the character ";"
187
template <>
188
[[nodiscard]] std::vector<bool> convertFromString<std::vector<bool>>(StringView str);
189

190
// Strings separated by the character ";"
191
template <>
192
[[nodiscard]] std::vector<std::string>
193
convertFromString<std::vector<std::string>>(StringView str);
194

195
// This recognizes either 0/1, true/false, TRUE/FALSE
196
template <>
197
[[nodiscard]] bool convertFromString<bool>(StringView str);
198

199
// Names with all capital letters
200
template <>
201
[[nodiscard]] NodeStatus convertFromString<NodeStatus>(StringView str);
202

203
// Names with all capital letters
204
template <>
205
[[nodiscard]] NodeType convertFromString<NodeType>(StringView str);
206

207
template <>
208
[[nodiscard]] PortDirection convertFromString<PortDirection>(StringView str);
209

210
using StringConverter = std::function<Any(StringView)>;
211

212
using StringConvertersMap = std::unordered_map<const std::type_info*, StringConverter>;
213

214
// helper function
215
template <typename T>
216
[[nodiscard]] inline StringConverter GetAnyFromStringFunctor()
16,071✔
217
{
218
  if constexpr(std::is_constructible_v<StringView, T>)
219
  {
220
    return [](StringView str) { return Any(str); };
8,093✔
221
  }
222
  else if constexpr(std::is_same_v<BT::AnyTypeAllowed, T> || std::is_enum_v<T>)
223
  {
224
    return {};
3,461✔
225
  }
226
  else
227
  {
228
    return [](StringView str) { return Any(convertFromString<T>(str)); };
6,087✔
229
  }
230
}
231

232
template <>
233
[[nodiscard]] inline StringConverter GetAnyFromStringFunctor<void>()
234
{
235
  return {};
236
}
237

238
//------------------------------------------------------------------
239

240
template <typename T>
241
constexpr bool IsConvertibleToString()
242
{
243
  return std::is_convertible_v<T, std::string> ||
244
         std::is_convertible_v<T, std::string_view>;
245
}
246

247
Expected<std::string> toJsonString(const Any& value);
248

249
/**
250
 * @brief toStr is the reverse operation of convertFromString.
251
 *
252
 * If T is a custom type and there is no template specialization,
253
 * it will try to fall back to toJsonString()
254
 */
255
template <typename T>
256
[[nodiscard]] std::string toStr(const T& value)
886✔
257
{
258
  if constexpr(IsConvertibleToString<T>())
259
  {
260
    return static_cast<std::string>(value);
22✔
261
  }
262
  else if constexpr(!std::is_arithmetic_v<T>)
263
  {
264
    if(auto str = toJsonString(Any(value)))
8✔
265
    {
266
      return *str;
2✔
267
    }
268

269
    throw LogicError(StrCat("Function BT::toStr<T>() not specialized for type [",
6✔
270
                            BT::demangle(typeid(T)), "]"));
271
  }
272
  else
273
  {
274
    return std::to_string(value);
868✔
275
  }
276
}
277

278
template <>
279
[[nodiscard]] std::string toStr<bool>(const bool& value);
280

281
template <>
282
[[nodiscard]] std::string toStr<std::string>(const std::string& value);
283

284
template <>
285
[[nodiscard]] std::string toStr<BT::NodeStatus>(const BT::NodeStatus& status);
286

287
/**
288
 * @brief toStr converts NodeStatus to string. Optionally colored.
289
 */
290
[[nodiscard]] std::string toStr(BT::NodeStatus status, bool colored);
291

292
std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status);
293

294
template <>
295
[[nodiscard]] std::string toStr<BT::NodeType>(const BT::NodeType& type);
296

297
std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
298

299
template <>
300
[[nodiscard]] std::string toStr<BT::PortDirection>(const BT::PortDirection& direction);
301

302
std::ostream& operator<<(std::ostream& os, const BT::PortDirection& type);
303

304
// Small utility, unless you want to use <boost/algorithm/string.hpp>
305
[[nodiscard]] std::vector<StringView> splitString(const StringView& strToSplit,
306
                                                  char delimeter);
307

308
template <typename Predicate>
309
using enable_if = typename std::enable_if<Predicate::value>::type*;
310

311
template <typename Predicate>
312
using enable_if_not = typename std::enable_if<!Predicate::value>::type*;
313

314
#ifdef USE_BTCPP3_OLD_NAMES
315
// note: we also use the name Optional instead of expected because it is more intuitive
316
// for users that are not up to date with "modern" C++
317
template <typename T>
318
using Optional = nonstd::expected<T, std::string>;
319
#endif
320

321
/** Usage: given a function/method like:
322
 *
323
 *     Result DoSomething();
324
 *
325
 * User code can check result and error message like this:
326
 *
327
 *     auto res = DoSomething();
328
 *     if( res )
329
 *     {
330
 *         std::cout << "DoSomething() done " << std::endl;
331
 *     }
332
 *     else{
333
 *         std::cerr << "DoSomething() failed with message: " << res.error() << std::endl;
334
 *     }
335
 *
336
 * */
337
using Result = Expected<std::monostate>;
338

339
struct Timestamp
340
{
341
  // Number being incremented every time a new value is written
342
  uint64_t seq = 0;
343
  // Last update time. Nanoseconds since epoch
344
  std::chrono::nanoseconds time = std::chrono::nanoseconds(0);
1,464✔
345
};
346

347
[[nodiscard]] bool IsAllowedPortName(StringView str);
348

349
[[nodiscard]] bool IsReservedAttribute(StringView str);
350

351
/// Returns the first forbidden character found in the name, or '\0' if valid.
352
/// Forbidden characters include: space, tab, newline, CR, < > & " ' / \ : * ? | .
353
/// and control characters (ASCII 0-31, 127). UTF-8 multibyte sequences are allowed.
354
[[nodiscard]] char findForbiddenChar(StringView name);
355

356
class TypeInfo
357
{
358
public:
359
  template <typename T>
360
  static TypeInfo Create()
88✔
361
  {
362
    return TypeInfo{ typeid(T), GetAnyFromStringFunctor<T>() };
88✔
363
  }
364

365
  TypeInfo() : type_info_(typeid(AnyTypeAllowed)), type_str_("AnyTypeAllowed")
31,506✔
366
  {}
15,753✔
367

368
  TypeInfo(std::type_index type_info, StringConverter conv)
16,072✔
369
    : type_info_(type_info), converter_(conv), type_str_(BT::demangle(type_info))
16,072✔
370
  {}
16,072✔
371

372
  [[nodiscard]] const std::type_index& type() const;
373

374
  [[nodiscard]] const std::string& typeName() const;
375

376
  [[nodiscard]] Any parseString(const char* str) const;
377

378
  [[nodiscard]] Any parseString(const std::string& str) const;
379

380
  template <typename T>
381
  [[nodiscard]] Any parseString(const T&) const
×
382
  {
383
    // avoid compilation errors
384
    return {};
×
385
  }
386

387
  [[nodiscard]] bool isStronglyTyped() const
380✔
388
  {
389
    return type_info_ != typeid(AnyTypeAllowed) && type_info_ != typeid(BT::Any);
380✔
390
  }
391

392
  [[nodiscard]] const StringConverter& converter() const
1,838✔
393
  {
394
    return converter_;
1,838✔
395
  }
396

397
private:
398
  std::type_index type_info_;
399
  StringConverter converter_;
400
  std::string type_str_;
401
};
402

403
class PortInfo : public TypeInfo
404
{
405
public:
406
  PortInfo(PortDirection direction = PortDirection::INOUT)
15,752✔
407
    : TypeInfo(), direction_(direction)
15,752✔
408
  {}
15,752✔
409

410
  PortInfo(PortDirection direction, std::type_index type_info, StringConverter conv)
15,984✔
411
    : TypeInfo(type_info, conv), direction_(direction)
15,984✔
412
  {}
15,984✔
413

414
  [[nodiscard]] PortDirection direction() const;
415

416
  void setDescription(StringView description);
417

418
  template <typename T>
419
  void setDefaultValue(const T& default_value)
2,907✔
420
  {
421
    default_value_ = Any(default_value);
2,907✔
422
    try
423
    {
424
      default_value_str_ = BT::toStr(default_value);
2,907✔
425
    }
426
    // NOLINTNEXTLINE(bugprone-empty-catch)
427
    catch(LogicError&)
6✔
428
    {
429
      // conversion to string not available for this type, ignore
430
    }
431
  }
2,907✔
432

433
  [[nodiscard]] const std::string& description() const;
434

435
  [[nodiscard]] const Any& defaultValue() const;
436

437
  [[nodiscard]] const std::string& defaultValueString() const;
438

439
private:
440
  PortDirection direction_;
441
  std::string description_;
442
  Any default_value_;
443
  std::string default_value_str_;
444
};
445

446
template <typename T = AnyTypeAllowed>
447
[[nodiscard]] std::pair<std::string, PortInfo> CreatePort(PortDirection direction,
15,637✔
448
                                                          StringView name,
449
                                                          StringView description = {})
450
{
451
  auto sname = static_cast<std::string>(name);
15,637✔
452
  if(!IsAllowedPortName(sname))
15,637✔
453
  {
454
    throw RuntimeError("The name of a port must not be `name` or `ID` "
1✔
455
                       "and must start with an alphabetic character. "
456
                       "Underscore is reserved.");
457
  }
458

459
  std::pair<std::string, PortInfo> out;
15,636✔
460

461
  if(std::is_same<T, void>::value)
462
  {
463
    out = { sname, PortInfo(direction) };
464
  }
465
  else
466
  {
467
    out = { sname, PortInfo(direction, typeid(T), GetAnyFromStringFunctor<T>()) };
15,636✔
468
  }
469
  if(!description.empty())
15,636✔
470
  {
471
    out.second.setDescription(description);
6,072✔
472
  }
473
  return out;
31,272✔
474
}
15,637✔
475

476
//----------
477
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::INPUT, ...)
478
 *
479
 *  @param name the name of the port
480
 *  @param description optional human-readable description
481
 */
482
template <typename T = AnyTypeAllowed>
483
[[nodiscard]] inline std::pair<std::string, PortInfo>
484
InputPort(StringView name, StringView description = {})
10,384✔
485
{
486
  return CreatePort<T>(PortDirection::INPUT, name, description);
10,384✔
487
}
488

489
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::OUTPUT,...)
490
 *
491
 *  @param name the name of the port
492
 *  @param description optional human-readable description
493
 */
494
template <typename T = AnyTypeAllowed>
495
[[nodiscard]] inline std::pair<std::string, PortInfo>
496
OutputPort(StringView name, StringView description = {})
1,198✔
497
{
498
  return CreatePort<T>(PortDirection::OUTPUT, name, description);
1,198✔
499
}
500

501
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::INOUT,...)
502
 *
503
 *  @param name the name of the port
504
 *  @param description optional human-readable description
505
 */
506
template <typename T = AnyTypeAllowed>
507
[[nodiscard]] inline std::pair<std::string, PortInfo>
508
BidirectionalPort(StringView name, StringView description = {})
1,437✔
509
{
510
  return CreatePort<T>(PortDirection::INOUT, name, description);
1,437✔
511
}
512
//----------
513

514
namespace details
515
{
516

517
template <typename T = AnyTypeAllowed, typename DefaultT = T>
518
[[nodiscard]] inline std::pair<std::string, PortInfo>
519
PortWithDefault(PortDirection direction, StringView name, const DefaultT& default_value,
2,609✔
520
                StringView description)
521
{
522
  static_assert(IsConvertibleToString<DefaultT>() || std::is_convertible_v<T, DefaultT> ||
523
                    std::is_constructible_v<T, DefaultT>,
524
                "The default value must be either the same of the port or string");
525

526
  auto out = CreatePort<T>(direction, name, description);
2,609✔
527

528
  if constexpr(std::is_constructible_v<T, DefaultT>)
529
  {
530
    out.second.setDefaultValue(T(default_value));
2,609✔
531
  }
532
  else if constexpr(IsConvertibleToString<DefaultT>())
533
  {
534
    out.second.setDefaultValue(std::string(default_value));
10✔
535
  }
536
  else
537
  {
538
    out.second.setDefaultValue(default_value);
539
  }
540
  return out;
2,609✔
541
}
×
542

543
}  // end namespace details
544

545
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::INPUT,...)
546
 *  It also sets the PortInfo::defaultValue()
547
 *
548
 *  @param name the name of the port
549
 *  @param default_value default value of the port, either type T of BlackboardKey
550
 *  @param description optional human-readable description
551
 */
552
template <typename T = AnyTypeAllowed, typename DefaultT = T>
553
[[nodiscard]] inline std::pair<std::string, PortInfo>
554
InputPort(StringView name, const DefaultT& default_value, StringView description)
2,608✔
555
{
556
  return details::PortWithDefault<T, DefaultT>(PortDirection::INPUT, name, default_value,
557
                                               description);
2,608✔
558
}
559

560
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::INOUT,...)
561
 *  It also sets the PortInfo::defaultValue()
562
 *
563
 *  @param name the name of the port
564
 *  @param default_value default value of the port, either type T of BlackboardKey
565
 *  @param description optional human-readable description
566
 */
567
template <typename T = AnyTypeAllowed, typename DefaultT = T>
568
[[nodiscard]] inline std::pair<std::string, PortInfo>
569
BidirectionalPort(StringView name, const DefaultT& default_value, StringView description)
1✔
570
{
571
  return details::PortWithDefault<T, DefaultT>(PortDirection::INOUT, name, default_value,
572
                                               description);
1✔
573
}
574

575
/** Syntactic sugar to invoke CreatePort<T>(PortDirection::OUTPUT,...)
576
 *  It also sets the PortInfo::defaultValue()
577
 *
578
 *  @param name the name of the port
579
 *  @param default_value default blackboard entry where the output is written
580
 *  @param description optional human-readable description
581
 */
582
template <typename T = AnyTypeAllowed>
583
[[nodiscard]] inline std::pair<std::string, PortInfo> OutputPort(StringView name,
9✔
584
                                                                 StringView default_value,
585
                                                                 StringView description)
586
{
587
  if(default_value.empty() || default_value.front() != '{' || default_value.back() != '}')
9✔
588
  {
UNCOV
589
    throw LogicError("Output port can only refer to blackboard entries, i.e. use the "
×
590
                     "syntax '{port_name}'");
591
  }
592
  auto out = CreatePort<T>(PortDirection::OUTPUT, name, description);
9✔
593
  out.second.setDefaultValue(default_value);
9✔
594
  return out;
9✔
UNCOV
595
}
×
596

597
//----------
598

599
using PortsList = std::unordered_map<std::string, PortInfo>;
600

601
template <typename T, typename = void>
602
struct has_static_method_providedPorts : std::false_type
603
{
604
};
605

606
template <typename T>
607
struct has_static_method_providedPorts<
608
    T, typename std::enable_if<
609
           std::is_same<decltype(T::providedPorts()), PortsList>::value>::type>
610
  : std::true_type
611
{
612
};
613

614
template <typename T, typename = void>
615
struct has_static_method_metadata : std::false_type
616
{
617
};
618

619
template <typename T>
620
struct has_static_method_metadata<
621
    T, typename std::enable_if<
622
           std::is_same<decltype(T::metadata()), KeyValueVector>::value>::type>
623
  : std::true_type
624
{
625
};
626

627
template <typename T>
628
[[nodiscard]] inline PortsList
629
getProvidedPorts(enable_if<has_static_method_providedPorts<T>> = nullptr)
7,580✔
630
{
631
  return T::providedPorts();
7,580✔
632
}
633

634
template <typename T>
635
[[nodiscard]] inline PortsList
636
getProvidedPorts(enable_if_not<has_static_method_providedPorts<T>> = nullptr)
4,311✔
637
{
638
  return {};
4,311✔
639
}
640

641
using TimePoint = std::chrono::high_resolution_clock::time_point;
642
using Duration = std::chrono::high_resolution_clock::duration;
643

644
}  // namespace BT
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc