行为树(BT)笔记(六):黑板

黑板是树的所有节点共享的键/值存储。

是一个字符串而是类型擦除容器(称为SafeAny::Any),其允许用户存储的任何C ++对象,并将它转换回其原始形式。

反之,以boost::anystd::anySafeAny::Any也将尽量避免共同溢和下溢错误。

事实上,你不能将一个负数转换成一个unsigned integer超过2 ^ 8的非大数字char

如果存储为字符串,黑板将使用convertFromString<T>() 它将其强制转换为类型T(参见前面的示例);

用户可以创建他/她自己的Blackboards后端; 例如,可以使用数据库创建持久性黑板。

将黑板分配给树

让我们从一个SimpleActionNode写入黑板开始。

// Write into the blackboard key: [GoalPose]
// Use this function to create a SimpleActionNode
NodeStatus CalculateGoalPose(TreeNode& self)
{
    const Pose2D mygoal = { 1, 2, 3.14};

    // RECOMMENDED: check if the blackboard is nullptr first
    if( self.blackboard() )
    {
        // store it in the blackboard
        self.blackboard()->set("GoalPose", mygoal);
        return NodeStatus::SUCCESS;
    }
    else{
        // No blackboard passed to this node.
        return NodeStatus::FAILURE;
    }
}

让我们考虑以下XML树定义:

 <root main_tree_to_execute = "MainTree">
     <BehaviorTree ID="MainTree">
        <SequenceStar>
            <CalculateGoalPose/>
            <MoveBase  goal="${GoalPose}" />
            <SetBlackboard key="OtherGoal" value="-1;3;0.5" />
            <MoveBase  goal="${OtherGoal}" />
        </SequenceStar>
     </BehaviorTree>
 </root>

根SequenceStar将执行四个动作:

  • CalculateGoalPose 写入黑板键“GoalPose”。
  • 语法${...}告诉MoveBase从黑板上读取运行时的目标; 黑板上的关键是“GoalPose”。
  • 或者,您可以使用内置操作将键/值对写入黑板SetBlackboard
  • 与步骤2类似。从“OtherGoal”键中检索Pose2D。
为了您的信息,GoalPose存储为类型删除Pose2D。

另一方面,OtherGoal存储为std :: string,但是通过getParam()使用该函数的方法转换为Pose2D convertFromString<Pose2D>()。

在下面的代码示例中,我们可以看到两种将Blackboard分配给树的等效方法。

int main()
{
    using namespace BT;

    BehaviorTreeFactory factory;
    factory.registerSimpleAction("CalculateGoalPose", CalculateGoalPose);
    factory.registerNodeType<MoveBaseAction>("MoveBase");

    // create a Blackboard from BlackboardLocal (simple, not persistent, local storage)
    auto blackboard = Blackboard::create<BlackboardLocal>();

    // Important: when the object tree goes out of scope, all the TreeNodes are destroyed
    auto tree = buildTreeFromText(factory, xml_text, blackboard);
    // alternatively:
    //  auto tree = buildTreeFromText(factory, xml_text);
    //  assignBlackboardToEntireTree( tree.root_node, blackboard );

    NodeStatus status = NodeStatus::RUNNING;
    while( status == NodeStatus::RUNNING )
    {
        status = tree.root_node->executeTick();
        SleepMS(1); // optional sleep to avoid "busy loops"
    }
    return 0;
}

/* Expected output

[ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.14
[ MoveBase: FINISHED ]
[ MoveBase: STARTED ]. goal: x=-1 y=3.0 theta=0.50
[ MoveBase: FINISHED ]
*/

 

  • 0
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值