概论

Behavior Tree

主要用于机器人和游戏AI,代替有限元状态机

特性:

  • 可以执行异步动作
  • 可以在运行时创建树
  • 可以把自定义的树转换成插件链接,在运行时动态加载
  • 包含日志/优化架构可以可视化,记录回放分析状态转移

什么是行为树?

行为树(BT)是一种结构在不同自动化终端任务之间转换,比如机器人或者游戏的虚拟实体

BT相对于FSM的优点:

  • 他们本质上是分层的
  • 他们的图形表示语言意义
  • 他们更具表现力

为什么需要行为树?

用于Component Based Software Engineering

好的软件架构有以下特性:

  • 模块化
  • 可重用的组件
  • 可压缩性
  • 好的关注点分离

基础学习

介绍BT

tick()触发

TreeNode触发,返回NodeStatus

  • SUCCESS
  • FAILURE
  • RUNNING

RUNNING表示异步执行

节点的种类

控制节点(ControlNodes),拥有1-N个子节点,接收到tick之后,tick会被传播到1个或多个子节点

装饰节点(DecoratorNodes),和控制节点相似,但是只有一个子节点

动作节点(ActionNodes),是树叶节点,没有子节点,用户需要通过实现自己的动作节点来执行实际的任务

条件节点(ConditionNodes),和动作节点相等,但是总是原子的和同步的,不能返回RUNNING状态,不能改变系统状态

Nodes

序列例子

BT使用最多的SequenceNode

控制节点的子节点都是有序的,从左到右执行

简单来说:

  • 子节点返回成功,tick下一个
  • 子节点返回失败,没有子节点将会tick,序列返回失败
  • 如果所有的子节点返回成功,序列返回成功

Decorator

目的:

  • 转换从子节点收到的结果
  • 停止子节点的执行
  • 重复tick子节点,取决于装饰节点的类型

Decorator

节点Inverter装饰器,把返回的值反转

节点Retry重复N次子节点

以上节点组合形式在门开了后会取消所有动作

FallbackNodes

又名为被理解为Selectors,是一些节点,顾名思义,可以表达回退策略,即如果一个子节点返回FAILURE,接下来该怎么做。

按照顺序触发:

  • 如果子节点返回失败,tick下个节点
  • 如果返回成功,不再tick节点,Fallback返回成功

fallback

教程

创建树

代码

 1#include <iostream>
 2#include <behaviortree_cpp_v3/bt_factory.h>
 3
 4class ApproachGripper : public BT::SyncActionNode
 5{
 6public:
 7    explicit ApproachGripper(const std::string &name) : BT::SyncActionNode(name, {})
 8    {}
 9
10    BT::NodeStatus tick() override
11    {
12        std::cout << "ApproachObject: " << name() << std::endl;
13        return BT::NodeStatus::SUCCESS;
14    }
15};
16
17bool batteryOK = false;
18
19BT::NodeStatus CheckBattery()
20{
21    if (batteryOK) {
22        std::cout << "[ Battery: OK ]" << std::endl;
23        return BT::NodeStatus::SUCCESS;
24    } else {
25        std::cout << "[ Battery: BAD ]" << std::endl;
26        return BT::NodeStatus::FAILURE;
27    }
28}
29
30BT::NodeStatus Charge()
31{
32    std::cout << "[ Charge Battery ]" << std::endl;
33    return BT::NodeStatus::SUCCESS;
34}
35
36class GripperInterface
37{
38public:
39    GripperInterface() : _open(true)
40    {}
41
42    BT::NodeStatus open()
43    {
44        _open = true;
45        std::cout << "GripperInterface::open" << std::endl;
46        return BT::NodeStatus::SUCCESS;
47    }
48
49    BT::NodeStatus close()
50    {
51        _open = false;
52        std::cout << "GripperInterface::close" << std::endl;
53        return BT::NodeStatus::SUCCESS;
54    }
55
56private:
57    bool _open;
58};
59
60int main()
61{
62    BT::BehaviorTreeFactory factory;
63    factory.registerNodeType<ApproachGripper>("ApproachGripper");
64    factory.registerSimpleCondition("CheckBattery",
65                                    [](BT::TreeNode &node) { return CheckBattery(); });
66    factory.registerSimpleCondition("Charge",
67                                    [](BT::TreeNode &node) { return Charge(); });
68    GripperInterface gripper;
69    factory.registerSimpleAction("OpenGripper",
70                                 [&gripper](BT::TreeNode &node) { return gripper.open(); });
71    factory.registerSimpleAction("CloseGripper",
72                                 [&gripper](BT::TreeNode &node) { return gripper.close(); });
73
74    auto tree = factory.createTreeFromFile("../my_tree1.xml");
75    tree.tickRoot();
76}
 1<?xml version="1.0"?>
 2<root main_tree_to_execute="BehaviorTree">
 3    <!-- ////////// -->
 4    <BehaviorTree ID="BehaviorTree">
 5        <Sequence>
 6            <Fallback>
 7                <Condition ID="CheckBattery"/>
 8                <Condition ID="Charge"/>
 9            </Fallback>
10            <Action ID="OpenGripper"/>
11            <Action ID="ApproachGripper"/>
12            <Action ID="CloseGripper"/>
13        </Sequence>
14    </BehaviorTree>
15    <!-- ////////// -->
16    <TreeNodesModel>
17        <Action ID="ApproachGripper"/>
18        <Condition ID="Charge"/>
19        <Condition ID="CheckBattery"/>
20        <Action ID="CloseGripper"/>
21        <Action ID="OpenGripper"/>
22    </TreeNodesModel>
23    <!-- ////////// -->
24</root>

执行后结果如下

[ Battery: BAD ]
[ Charge Battery ]
GripperInterface::open
ApproachObject: ApproachGripper
GripperInterface::close

<TreeNodesModel>节点才能正常用Groot读取

输入和输出接口

行为树支持用接口(ports)传输数据流,使用简单而且类型安全

输入接口

正确的输入具备:

  • 静态的字符串可以被节点解析
  • 指向blackboard上一个条目的“指针”,由一个键识别

blackboard是所有节点共享的简单的 键/值存储

blackboard的一个entry相当于一个键/值对(语义参考数据库)

输入接口可以读取blackboard中的entry,输出口可以写entry

输出接口

输出口可以是字符串也可以是blackboard的一个entry

类似{the_answer}的字符串代表blackboard上名字叫the_answer的条目

代码

 1//
 2// Created by jiang on 2021/9/18.
 3//
 4
 5#include <behaviortree_cpp_v3/action_node.h>
 6#include <behaviortree_cpp_v3/bt_factory.h>
 7
 8using namespace BT;
 9
10class SaySomething : public SyncActionNode
11{
12public:
13    SaySomething(const std::string &name, const NodeConfiguration &config) :
14            SyncActionNode(name, config)
15    {}
16
17    static PortsList providedPorts()
18    {
19        return {InputPort<std::string>("message")};
20    }
21
22protected:
23    NodeStatus tick() override
24    {
25        Optional<std::string> msg = getInput<std::string>("message");
26        if (!msg) {
27            throw RuntimeError("missing required input [message]: ", msg.error());
28        }
29        std::cout << "Robot says: " << msg.value() << std::endl;
30        return NodeStatus::SUCCESS;
31    }
32};
33
34NodeStatus SaySomethingSimple(TreeNode &self)
35{
36    Optional<std::string> msg = self.getInput<std::string>("message");
37    if (!msg) {
38        throw RuntimeError("missing required input [message]: ", msg.error());
39    }
40    std::cout << "Robot says: " << msg.value() << std::endl;
41    return NodeStatus::SUCCESS;
42}
43
44class ThinkWhatToSay : public SyncActionNode
45{
46public:
47    ThinkWhatToSay(const std::string &name, const NodeConfiguration &config) :
48            SyncActionNode(name, config)
49    {}
50
51    static PortsList providedPorts()
52    {
53        return {OutputPort<std::string>("text")};
54    }
55
56protected:
57    NodeStatus tick() override
58    {
59        setOutput("text", "The answer is 42");
60        return NodeStatus::SUCCESS;
61    }
62};
63
64int main()
65{
66    BehaviorTreeFactory factory;
67    factory.registerNodeType<SaySomething>("SaySomething");
68    factory.registerNodeType<ThinkWhatToSay>("ThinkWhatToSay");
69
70    PortsList saySomethingPorts = {InputPort<std::string>("message")};
71    factory.registerSimpleAction("SaySomething2", SaySomethingSimple, saySomethingPorts);
72    auto tree = factory.createTreeFromFile("../../test_port/port1.xml");
73    tree.tickRoot();
74    return 0;
75}
 1<?xml version="1.0"?>
 2<root main_tree_to_execute="BehaviorTree">
 3    <!-- ////////// -->
 4    <BehaviorTree ID="BehaviorTree">
 5        <Sequence>
 6            <Action ID="SaySomething" message="start thinking..."/>
 7            <Action ID="ThinkWhatToSay" text="{the_answer}"/>
 8            <Action ID="SaySomething" message="{the_answer}"/>
 9            <Action ID="SaySomething2" message="say something 2 works"/>
10            <Action ID="SaySomething2" message="{the_answer}"/>
11        </Sequence>
12    </BehaviorTree>
13    <!-- ////////// -->
14    <TreeNodesModel>
15        <Action ID="SaySomething">
16            <input_port name="message"/>
17        </Action>
18        <Action ID="SaySomething2">
19            <input_port name="message"/>
20        </Action>
21        <Action ID="ThinkWhatToSay">
22            <output_port name="text"/>
23        </Action>
24    </TreeNodesModel>
25    <!-- ////////// -->
26</root>

通用接口

通过重载模板函数使得可以把字符串转成自定义的类结构

 1template <typename T>
 2inline T convertFromString(StringView str);
 3
 4// 例如
 5struct Position2D
 6{
 7  double x;
 8  double y;
 9};
10
11namespace BT
12{
13    template <> inline Position2D convertFromString(StringView str)
14    {
15        // The next line should be removed...
16        printf("Converting string: \"%s\"\n", str.data() );
17
18        // We expect real numbers separated by semicolons
19        auto parts = splitString(str, ';');
20        if (parts.size() != 2)
21        {
22            throw RuntimeError("invalid input)");
23        }
24        else{
25            Position2D output;
26            output.x     = convertFromString<double>(parts[0]);
27            output.y     = convertFromString<double>(parts[1]);
28            return output;
29        }
30    }
31} // end namespace BT

注册接口使用

1static PortsList providedPorts()
2{
3    // Optionally, a port can have a human readable description
4    const char*  description = "Simply print the goal on console...";
5    return { InputPort<Position2D>("target", description) };
6}

在xml文件中使用

1<SequenceStar name="root">
2    <CalculateGoal   goal="{GoalPosition}" />
3    <PrintTarget     target="{GoalPosition}" />
4    <SetBlackboard   output_key="OtherGoal" value="-1;3" />
5    <PrintTarget     target="{OtherGoal}" />
6</SequenceStar>

序列和异步动作节点

SequenceNodeReactiveSequence的区别

异步的动作有自己的线程。这允许用户使用阻塞函数,但要把执行的流程返回给树。

机器人移动例子:

  1//
  2// Created by jiang on 2021/9/18.
  3//
  4
  5#include <behaviortree_cpp_v3/bt_factory.h>
  6#include <behaviortree_cpp_v3/action_node.h>
  7#include <thread>
  8
  9using namespace BT;
 10
 11inline void SleepMS(int ms)
 12{
 13    std::this_thread::sleep_for(std::chrono::milliseconds(ms));
 14}
 15
 16struct Pose2D
 17{
 18    double x;
 19    double y;
 20    double theta;
 21};
 22namespace BT
 23{
 24
 25template<>
 26inline Pose2D convertFromString(StringView str)
 27{
 28    auto parts = splitString(str, ';');
 29    if (parts.size() != 3) {
 30        throw RuntimeError("invalid input)");
 31    } else {
 32        Pose2D output{
 33                convertFromString<double>(parts[0]),
 34                convertFromString<double>(parts[1]),
 35                convertFromString<double>(parts[2]),
 36        };
 37        return output;
 38    }
 39}
 40}
 41
 42class MoveBaseAction : public AsyncActionNode
 43{
 44public:
 45    MoveBaseAction(const std::string &name, const NodeConfiguration &config) :
 46            AsyncActionNode(name, config)
 47    {}
 48
 49    static PortsList providedPorts()
 50    {
 51        return {InputPort<Pose2D>("goal")};
 52    }
 53
 54protected:
 55    NodeStatus tick() override;
 56};
 57
 58NodeStatus MoveBaseAction::tick()
 59{
 60    std::cout << "move base thread id: " << std::this_thread::get_id();
 61    Pose2D goal{};
 62    if (!getInput<Pose2D>("goal", goal)) {
 63        throw RuntimeError("missing required input [goal]");
 64    }
 65    printf("[MoveBase STATED]. goal: x=%.f y = %.1f theta=%.2f\n", goal.x, goal.y, goal.theta);
 66    int count = 0;
 67    while (!isHaltRequested() && count++ < 25) {
 68        SleepMS(10);
 69    }
 70    std::cout << "[MoveBase FINISHED]" << std::endl;
 71    return isHaltRequested() ? NodeStatus::FAILURE : NodeStatus::SUCCESS;
 72}
 73
 74class SaySomething : public SyncActionNode
 75{
 76public:
 77    SaySomething(const std::string &name, const NodeConfiguration &config) :
 78            SyncActionNode(name, config)
 79    {}
 80
 81    static PortsList providedPorts()
 82    {
 83        return {InputPort<std::string>("message")};
 84    }
 85
 86protected:
 87    NodeStatus tick() override
 88    {
 89        Optional<std::string> msg = getInput<std::string>("message");
 90        if (!msg) {
 91            throw RuntimeError("missing required input [message]: ", msg.error());
 92        }
 93        std::cout << "Robot says: " << msg.value() << std::endl;
 94        return NodeStatus::SUCCESS;
 95    }
 96};
 97
 98NodeStatus CheckBattery(TreeNode &node)
 99{
100    std::cout << "[ Battery: OK ]" << std::endl;
101    return NodeStatus::SUCCESS;
102}
103
104int main()
105{
106    BehaviorTreeFactory factory;
107    factory.registerSimpleCondition("BatteryOK", CheckBattery);
108    factory.registerNodeType<MoveBaseAction>("MoveBase");
109    factory.registerNodeType<SaySomething>("SaySomething");
110
111    auto tree = factory.createTreeFromFile("../../test_async/async.xml");
112
113    NodeStatus status;
114
115    std::cout << "main thread id: " << std::this_thread::get_id();
116
117    std::cout << "\n--- 1st executeTick() --- " << std::endl;
118    status = tree.tickRoot();
119    std::cout << "result : " << status << std::endl;
120
121    SleepMS(150);
122    std::cout << "\n--- 2nd executeTick() ---" << std::endl;
123    status = tree.tickRoot();
124    std::cout << "result : " << status << std::endl;
125
126    SleepMS(150);
127    std::cout << "\n--- 3rd executeTick() ---" << std::endl;
128    status = tree.tickRoot();
129    std::cout << "result : " << status << std::endl;
130
131    std::cout << std::endl;
132
133    return 0;
134}
 1<?xml version="1.0"?>
 2<root main_tree_to_execute="BehaviorTree">
 3    <BehaviorTree ID="BehaviorTree">
 4        <Sequence>
 5            <Action ID="BatteryOK"/>
 6            <Action ID="SaySomething" message="mission started..."/>
 7            <Action ID="MoveBase" goal="1.0;2.0;3.0"/>
 8            <Action ID="SaySomething" message="mission completed!"/>
 9        </Sequence>
10    </BehaviorTree>
11
12    <TreeNodesModel>
13        <Action ID="SaySomething">
14            <input_port name="message"/>
15        </Action>
16        <Action ID="MoveBase">
17            <input_port name="goal"/>
18        </Action>
19    </TreeNodesModel>
20</root>

MoveBaseAction::tick()在线程中执行,而MoveBaseAction::executeTick()是在主线程中执行

有责任去实现halt()函数实现停止任务的功能

第一次和第二次都是最终返回RUNNING,第三次返回SUCCESS

RUNNING对于序列来说会停止执行后续任务

子树和日志

子树意味着可以创建分层的行为树,用很多小的可复用的行为树来组成大的行为树

例子

 1<root main_tree_to_execute = "MainTree">
 2
 3    <BehaviorTree ID="DoorClosed">
 4        <Sequence name="door_closed_sequence">
 5            <Inverter>
 6                <IsDoorOpen/>
 7            </Inverter>
 8            <RetryUntilSuccesful num_attempts="4">
 9                <OpenDoor/>
10            </RetryUntilSuccesful>
11            <PassThroughDoor/>
12        </Sequence>
13    </BehaviorTree>
14
15    <BehaviorTree ID="MainTree">
16        <Fallback name="root_Fallback">
17            <Sequence name="door_open_sequence">
18                <IsDoorOpen/>
19                <PassThroughDoor/>
20            </Sequence>
21            <SubTree ID="DoorClosed"/>
22            <PassThroughWindow/>
23        </Fallback>
24    </BehaviorTree>
25
26</root>

使用<SubTree ID="DoorClosed"/>调用子树

日志是用来显示记录发布状态改变的机制

 1int main()
 2{
 3    using namespace BT;
 4    BehaviorTreeFactory factory;
 5
 6    // register all the actions into the factory
 7    // We don't show how these actions are implemented, since most of the
 8    // times they just print a message on screen and return SUCCESS.
 9    // See the code on Github for more details.
10    factory.registerSimpleCondition("IsDoorOpen", std::bind(IsDoorOpen));
11    factory.registerSimpleAction("PassThroughDoor", std::bind(PassThroughDoor));
12    factory.registerSimpleAction("PassThroughWindow", std::bind(PassThroughWindow));
13    factory.registerSimpleAction("OpenDoor", std::bind(OpenDoor));
14    factory.registerSimpleAction("CloseDoor", std::bind(CloseDoor));
15    factory.registerSimpleCondition("IsDoorLocked", std::bind(IsDoorLocked));
16    factory.registerSimpleAction("UnlockDoor", std::bind(UnlockDoor));
17
18    // Load from text or file...
19    auto tree = factory.createTreeFromText(xml_text);
20
21    // This logger prints state changes on console
22    StdCoutLogger logger_cout(tree);
23
24    // This logger saves state changes on file
25    FileLogger logger_file(tree, "bt_trace.fbl");
26
27    // This logger stores the execution time of each node
28    MinitraceLogger logger_minitrace(tree, "bt_trace.json");
29
30#ifdef ZMQ_FOUND
31    // This logger publish status changes using ZeroMQ. Used by Groot
32    PublisherZMQ publisher_zmq(tree);
33#endif
34
35    printTreeRecursively(tree.rootNode());
36
37    //while (1)
38    {
39        NodeStatus status = NodeStatus::RUNNING;
40        // Keep on ticking until you get either a SUCCESS or FAILURE state
41        while( status == NodeStatus::RUNNING)
42        {
43            status = tree.tickRoot();
44            CrossDoor::SleepMS(1);   // optional sleep to avoid "busy loops"
45        }
46        CrossDoor::SleepMS(2000);
47    }
48    return 0;
49}

Groot使用ZMQ发布的状态信息

接口重映设

在CrossDoor的例子中,我们看到子树从其父节点(例子中的MainTree)的角度看就像一个单叶节点。此外,为了避免在非常大的树中出现名称冲突,任何树和子树都使用不同的blackboard实例。

由于这个原因,我们需要明确地将一棵树的端口与它的子树的端口连接起来。

例子

 1<root main_tree_to_execute = "MainTree">
 2
 3    <BehaviorTree ID="MainTree">
 4
 5        <Sequence name="main_sequence">
 6            <SetBlackboard output_key="move_goal" value="1;2;3" />
 7            <SubTree ID="MoveRobot" target="move_goal" output="move_result" />
 8            <SaySomething message="{move_result}"/>
 9        </Sequence>
10
11    </BehaviorTree>
12
13    <BehaviorTree ID="MoveRobot">
14        <Fallback name="move_robot_main">
15            <SequenceStar>
16                <MoveBase       goal="{target}"/>
17                <SetBlackboard output_key="output" value="mission accomplished" />
18            </SequenceStar>
19            <ForceFailure>
20                <SetBlackboard output_key="output" value="mission failed" />
21            </ForceFailure>
22        </Fallback>
23    </BehaviorTree>
24
25</root>
  • MoveRobot是一个子树,被包含于MainTree
  • 想要把MoveRobot的端口和MainTree的端口连接起来
  • 使用XML标签,其中internal/external这两个词分别指的是子树和其父树

<SubTree ID="MoveRobot" target="move_goal" output="move_result" />

把move_goal传入子树的target,把子树的结果output传出到move_result

remap

包装遗留代码

使用λ函数

 1class LegacyClass {
 2public:
 3    bool method() {
 4        return true;
 5    }
 6}
 7
 8LegacyClass legacy;
 9auto wrapFunc = [&legacy] (NodeTree &node) -> NodeStatus {
10    ...
11    return ...
12}
13
14PortsList ports = { ... };
15factory.registerSimpleAction("...", wrapFunc, ports);
16
17...

附加参数

方法1:使用NodeBuilder

假如节点的构造函数有更多的参数

1Action_A(const std::string& name, const NodeConfiguration& config,
2             int arg1, double arg2, std::string arg3 ):
3        SyncActionNode(name, config),
4        _arg1(arg1),
5        _arg2(arg2),
6        _arg3(arg3) {}

这时创建一个NodeBuilder函数

1NodeBuilder builder_A =
2   [](const std::string& name, const NodeConfiguration& config)
3{
4    return std::make_unique<Action_A>( name, config, 42, 3.14, "hello world" );
5};

再传入注册函数的第二个参数中去

1factory.registerBuilder<Action_A>( "Action_A", builder_A);

方法2:使用初始化方法

1void init( int arg1, double arg2, const std::string& arg3 )
2{
3    _arg1 = (arg1);
4    _arg2 = (arg2);
5    _arg3 = (arg3);
6}

使用C++ RTTI根据类型调用函数

1for( auto& node: tree.nodes )
2{
3    if( auto action_B = dynamic_cast<Action_B*>( node.get() ))
4    {
5        action_B->init( 42, 3.14, "hello world");
6    }
7}

协程

行为树提供了两种方便使用的创建异步动作的抽象,对于以下动作:

  • 花费很长的时间结束
  • 可能会返回RUNNING
  • 能够被停止

第一种类为AsyncActionNode,在隔离的线程中执行tick()函数

在本教程中引入CoroActionNode,使用协程来完成相似结果的动作

协程不会产生新的线程同时更有效率,而且不需要担心线程安全问题

在协程中,当用户想让执行的动作取消,需要显式调用yield方法

CoroActionNode封装了yield函数到setStatusRunningYield()

例子

 1typedef std::chrono::milliseconds Milliseconds;
 2
 3class MyAsyncAction: public CoroActionNode
 4{
 5  public:
 6    MyAsyncAction(const std::string& name):
 7        CoroActionNode(name, {})
 8    {}
 9
10  private:
11    // This is the ideal skeleton/template of an async action:
12    //  - A request to a remote service provider.
13    //  - A loop where we check if the reply has been received.
14    //  - You may call setStatusRunningAndYield() to "pause".
15    //  - Code to execute after the reply.
16    //  - A simple way to handle halt().
17    NodeStatus tick() override
18    {
19        std::cout << name() <<": Started. Send Request to server." << std::endl;
20
21        TimePoint initial_time = Now();
22        TimePoint time_before_reply = initial_time + Milliseconds(100);
23
24        int count = 0;
25        bool reply_received = false;
26
27        while( !reply_received )
28        {
29            if( count++ == 0)
30            {
31                // call this only once
32                std::cout << name() <<": Waiting Reply..." << std::endl;
33            }
34            // pretend that we received a reply
35            if( Now() >= time_before_reply )
36            {
37                reply_received = true;
38            }
39
40            if( !reply_received )
41            {
42                // set status to RUNNING and "pause/sleep"
43                // If halt() is called, we will NOT resume execution
44                setStatusRunningAndYield();
45            }
46        }
47
48        // This part of the code is never reached if halt() is invoked,
49        // only if reply_received == true;
50        std::cout << name() <<": Done. 'Waiting Reply' loop repeated "
51                  << count << " times" << std::endl;
52        cleanup(false);
53        return NodeStatus::SUCCESS;
54    }
55
56    // you might want to cleanup differently if it was halted or successful
57    void cleanup(bool halted)
58    {
59        if( halted )
60        {
61            std::cout << name() <<": cleaning up after an halt()\n" << std::endl;
62        }
63        else{
64            std::cout << name() <<": cleaning up after SUCCESS\n" << std::endl;
65        }
66    }
67
68    void halt() override
69    {
70        std::cout << name() <<": Halted." << std::endl;
71        cleanup(true);
72        // Do not forget to call this at the end.
73        CoroActionNode::halt();
74    }
75
76    Timepoint Now()
77    {
78        return std::chrono::high_resolution_clock::now();
79    };
80};
 1 <root >
 2     <BehaviorTree>
 3        <Timeout msec="150">
 4            <SequenceStar name="sequence">
 5                <MyAsyncAction name="action_A"/>
 6                <MyAsyncAction name="action_B"/>
 7            </SequenceStar>
 8        </Timeout>
 9     </BehaviorTree>
10 </root>