datetime:2023/05/11 15:12
author:nzb

BT5:DecoratorNodes源码解析

DecoratorNode基类

BehaviorTree.CPP中内建的装饰节点如下,都继承自 BehaviorTree.CPP\include\behaviortree_cpp_v3\decorator_node.h 中的DecoratorNode类。 很明显,该类只有1个子节点。ROS中也定义了一些方便使用的ControlNodesDecoratorNodes,可以导入使用。

class DecoratorNode : public TreeNode {
  protected:
    TreeNode* child_node_;
  ... ...
}

  • executeTick()
    • 如果子节点状态为SUCCESSFAILURE,调用子节点的resetStatus(),子节点状态变为IDEL

BlackboardPreconditionNode

细分为3个节点:BlackboardCheckIntBlackboardCheckDoubleBlackboardCheckString。顾名思义,该节点是检查blackboard的某个port的值是否符合预期的。

包含3个InputPort,当value_Avalue_B的值相等时,执行子节点。否则,不执行子节点,并返回return_on_mismatch设定的值。

static PortsList providedPorts() {
    return {InputPort("value_A"),
            InputPort("value_B"),
            InputPort<NodeStatus>("return_on_mismatch") };
}

源代码中使用==来判断2个变量的值,对于double类型不妥。

template <typename T>
inline NodeStatus BlackboardPreconditionNode<T>::tick() {
  T value_A;
  T value_B;
  NodeStatus default_return_status = NodeStatus::FAILURE;
  setStatus(NodeStatus::RUNNING);

  if (getInput("value_A", value_A) && getInput("value_B", value_B) &&
      value_B == value_A) {
    return child_node_->executeTick();
  }
  if (child()->status() == NodeStatus::RUNNING) {
    haltChild();
  }
  getInput("return_on_mismatch", default_return_status);
  return default_return_status;
}

示例:


<BlackboardCheckInt value_A="{the_answer}"
                    value_B="42"
                    return_on_mismatch="FAILURE"/>

DelayNode

延时delay_msec毫秒后,执行子节点,并返回子节点的执行结果。延时期间,返回RUNNING

static PortsList providedPorts() {
    return {InputPort<unsigned>("delay_msec", "Tick the child after a few milliseconds")};
}

示例:


<Delay delay_msec="5000">
    <KeepYourBreath/>
</Delay>

ForceFailureNode

如果子节点执行后返回RUNNING,该节点返回RUNNING;否则,该节点返回FAILURE,即强制返回失败状态。

ForceSuccessNodeForceFailureNode大同小异。

InverterNode

如果子节点执行后返回RUNNING,该节点返回RUNNING

如果子节点执行后返回SUCCESS,该节点返回FAILURE

如果子节点执行后返回FAILURE,该节点返回SUCCESS

即对子节点的执行结果取反。

KeepRunningUntilFailureNode

如果子节点执行后返回RUNNINGSUCCESS,下次tick()继续执行子节点,直到子节点返回FAILURE

RepeatNode

重复执行子节点NUM_CYCLES 次,若每次都返回 SUCCESS,该节点返回SUCCESS

若子节点某次返回FAILURE,该节点不再重复执行子节点,立即返回FAILURE

若子节点返回RUNNING,该节点也返回RUNNING

static PortsList providedPorts() {
    return { InputPort<int>(NUM_CYCLES,
                            "Repeat a succesful child up to N times. "
                            "Use -1 to create an infinite loop.") };
}

示例:


<Repeat num_cycles="3">
    <ClapYourHandsOnce/>
</Repeat>

RetryNode(RetryUntilSuccessful)

  • 如果子节点执行后返回RUNNING,该节点返回RUNNING

  • 如果子节点执行后返回SUCCESS,重置子节点resetChild(),该节点返回SUCCESS,不再执行;

  • 如果子节点执行后返回FAILURE

    • 重置子节点resetChild(),子节点变回IDLE
    • 再次尝试执行子节点,直到尝试了num_attempts次或-1直到成功;
static PortsList providedPorts() {
    return { InputPort<int>(NUM_ATTEMPTS,
                           "Execute again a failing child up to N times. "
                           "Use -1 to create an infinite loop.") };
}

示例:


<RetryUntilSuccesful num_attempts="3">
    <OpenDoor/>
</RetryUntilSuccesful>

SubtreeNode

用来封装一个subtree,这样会有一个独立的blackboard__shared_blackboard port的默认值是false,因此开发者要自行重映射端口。 但tick() 函数中并没有使用__shared_blackboard port,而是在 BehaviorTree.CPP\src\xml_parsing.cpp中使用的,这点要注意,SubtreePlusNode__autoremap port也是如此。

static PortsList providedPorts() {
    return { InputPort<bool>("__shared_blackboard", false,
                             "If false (default) the subtree has its own blackboard and you"
                             "need to do port remapping to connect it to the parent") };
}

SubtreePlusNode

控制重映射的强化版SubtreeNode。当__autoremap porttrue时,会自动重映射名称相同的port。结合代码示例会更容易理解。

static PortsList providedPorts() {
    return { InputPort<bool>("__autoremap", false,
                             "If true, all the ports with the same name will be remapped") };
}

示例:


<root main_tree_to_execute="MainTree">
    <BehaviorTree ID="MainTree">
        <Sequence>
            <!--第一种-->
            <SetBlackboard value="Hello" output_key="myParam"/>
            <SubTreePlus ID="Talk" param="{myParam}"/>
            <!--第二种-->
            <SubTreePlus ID="Talk" param="World"/>
            <!--第三种-->
            <SetBlackboard value="Auto remapped" output_key="param"/>
            <SubTreePlus ID="Talk" __autoremap="1"/>

        </Sequence>
    </BehaviorTree>

    <BehaviorTree ID="Talk">
        <SaySomething message="{param}"/>
    </BehaviorTree>
</root>

上面有3种重映射的实现方式。第1、2种是最常见的。

  • 第1种将Subtreeblackboardparam entry映射到Parent treeblackboardmyParam entry,将其值设置为字符串"Hello"。

  • 第2种将Subtreeblackboardparam entry的值直接设置为字符串"World"。

  • 第3种在Parent treeblackboard中增加了param entry,没有指定映射到subtree的哪个port。但由于设定__autoremap=true, 该entry 会自动映射到subtreeblackboardparam entrySaySomething节点会在其message port中获取到值为字符串“Auto remapped”。

TimeoutNode

在设置的msec 毫秒内,返回子节点执行的状态。若子节点返回FAILURESUCCESS,不再执行。如果超时,终止子节点执行,并返回FAILURE。 类中使用了TimerQueue 作为计时器,可以定时多个任务,比较有趣。

static PortsList providedPorts() {
    return { InputPort<unsigned>("msec", "After a certain amount of time, "
                                         "halt() the child if it is still running.") };
}

示例:

<Timeout msec="5000">
   <KeepYourBreath/>
</Timeout>

RateController

  • 频率控制
  • 参数:hz
  • tick子节点条件
    • 第一次节点处于IDLE状态
    • 子节点是RUNNING状态
    • 达到频率设置周期
  • 返回
    • 如果子节点执行后返回RUNNING,该节点返回RUNNING
    • 如果子节点执行后返回SUCCESS,该节点返回SUCCESS,重置开始时间;
    • 如果子节点执行后返回FAILURE,该节点返回FAILURE

results matching ""

    No results matching ""