行为树 — [5] Sequence节点

上一篇文章里讲了如何构建一颗简单树,里面使用了Sequence节点,本文则讲述Sequence节点的使用细节。


一 概念解释

Sequence的中文意思是顺序,次序,表示这个节点下的children需要按顺序执行,一个执行成功才可以执行下一个,有一个child执行失败,那么就表示整个Sequence执行失败。

Sequence节点分为以下三种,

  • Sequence (同名)
  • SequenceStar
  • ReactiveSequence

它们的区别如下,
在这里插入图片描述

  • Restart的意思是从第一个child开始重新运行整个树
  • Tick again的意思是下一次收到tick信号,只执行当前正在运行child,之前运行成功的child不会再运行

二 代码解释

首先规划一下行为树,
在这里插入图片描述
比较简单,就是开门->进屋->关门,需要注意一点,每个行为都要执行成功才可以执行下一个行为。例如如果门打不开,那就进不了屋。

本文只测试返回失败时的情况,返回RUNNING以后再测。

1. Sequence

xml内容如下,

<root main_tree_to_execute = "MainTree" >

     <BehaviorTree ID="MainTree">
        <Sequence name="root_sequence">
            <OpenDoor   name="open_door_of_house"/>
            <EnterHouse name="enter_house"/>
            <CloseDoor  name="close_door_of_house"/>
        </Sequence>
     </BehaviorTree>

 </root>

这里对进屋的child实现进行一点修改,增加一个成员变量m_iCnt,在tick函数里当这m_iCnt变成5时才返回成功,

class EnterHouseImpl : public BT::SyncActionNode
{
public:
    EnterHouseImpl(const std::string& name) :
        BT::SyncActionNode(name, {}), 
        m_iCnt(0)
    {
    }

    // You must override the virtual function tick()
    BT::NodeStatus tick() override
    {
        std::cout << "Enter house: ";
        if (++m_iCnt == 5)
        {
            m_iCnt = 0;
            std::cout << "success\\n";
            return BT::NodeStatus::SUCCESS;
        }
        else
        {
            std::cout << "failure\\n";
            return BT::NodeStatus::FAILURE;
        }
        
    }

private:
    int m_iCnt;
};

整体代码如下,

#include "behaviortree_cpp_v3/bt_factory.h"


static const char* xml_text = R"(

<root main_tree_to_execute = "MainTree" >

     <BehaviorTree ID="MainTree">
        <Sequence name="root_sequence">
            <OpenDoor   name="open_door_of_house"/>
            <EnterHouse name="enter_house"/>
            <CloseDoor  name="close_door_of_house"/>
        </Sequence>
     </BehaviorTree>

 </root>
 )";


class OpenDoorImpl : public BT::SyncActionNode
{
public:
    OpenDoorImpl(const std::string& name) :
        BT::SyncActionNode(name, {})
    {
    }

    // You must override the virtual function tick()
    BT::NodeStatus tick() override
    {
        std::cout << "Door is opened" << std::endl;
        return BT::NodeStatus::SUCCESS;
    }
};

class EnterHouseImpl : public BT::SyncActionNode
{
public:
    EnterHouseImpl(const std::string& name) :
        BT::SyncActionNode(name, {}), 
        m_iCnt(0)
    {
    }

    // You must override the virtual function tick()
    BT::NodeStatus tick() override
    {
        std::cout << "Enter house: ";
        if (++m_iCnt == 5)
        {
            m_iCnt = 0;
            std::cout << "success\\n";
            return BT::NodeStatus::SUCCESS;
        }
        else
        {
            std::cout << "failure\\n";
            return BT::NodeStatus::FAILURE;
        }
        
    }

private:
    int m_iCnt;
};

class CloseDoorImpl : public BT::SyncActionNode
{
public:
    CloseDoorImpl(const std::string& name) :
        BT::SyncActionNode(name, {})
    {
    }

    // You must override the virtual function tick()
    BT::NodeStatus tick() override
    {
        std::cout << "Close door" << std::endl;
        return BT::NodeStatus::SUCCESS;
    }
};


int main()
{
    // We use the BehaviorTreeFactory to register our custom nodes
    BT::BehaviorTreeFactory factory;


    factory.registerNodeType<OpenDoorImpl>("OpenDoor");
    factory.registerNodeType<EnterHouseImpl>("EnterHouse");
    factory.registerNodeType<CloseDoorImpl>("CloseDoor");


    auto tree = factory.createTreeFromText(xml_text);


    BT::NodeStatus status;
    while (true)
    {
        status = tree.tickRoot();
        if (status == BT::NodeStatus::SUCCESS)
        {
            break;
        }
    }

    return 0;
}

在main函数里,加一个while循环,只有当整个Sequence返回成功时才跳出来。最后执行结果如下,
在这里插入图片描述
可以看出,前面4次进屋失败,第5次进屋成功,进屋失败后会重新tick,这样会把整棵树重新运行一下,所以开门每次都重新执行了一下。

2. ReactiveSequence

代码和Sequence基本相同,只是把xml内容改一下,用ReactiveSequence代替Sequence

<root main_tree_to_execute = "MainTree" >

     <BehaviorTree ID="MainTree">
        <ReactiveSequence name="root_sequence">
            <OpenDoor   name="open_door_of_house"/>
            <EnterHouse name="enter_house"/>
            <CloseDoor  name="close_door_of_house"/>
        </ReactiveSequence>
     </BehaviorTree>

 </root>

返回失败时的处理和Sequence一样,也是restart,所以运行结果一样,
在这里插入图片描述

3. SequenceStar

同样只需修改xml内容,用SequenceStar代替Sequence,

<root main_tree_to_execute = "MainTree" >

     <BehaviorTree ID="MainTree">
        <SequenceStar name="root_sequence">
            <OpenDoor   name="open_door_of_house"/>
            <EnterHouse name="enter_house"/>
            <CloseDoor  name="close_door_of_house"/>
        </SequenceStar>
     </BehaviorTree>

 </root>

最后运行结果如下,
在这里插入图片描述
可以看出开门执行成功后就不会再重复执行了。


三 总结

本文讲述了Sequence节点的三种类型,以及在child返回失败时重新tick后的操作。

© 版权声明
THE END
喜欢就支持一下吧
点赞662 分享
评论 抢沙发
头像
欢迎您留下宝贵的见解!
提交
头像

昵称

取消
昵称表情代码图片

    暂无评论内容