**
behavior tree常用语法
**
在学习ros2 navigation2过程中,始终围绕着BT行为树(behavior tree)展开。
但这个东西太过于隐晦(其实看底层c++代码就明白了),因为完全不了解节点的特性,阅读起来非常吃力。
更是无从下手。
所以今天总结一些常用的BT节点,增强自己的记忆。
参考资料BehaviorTree.cpp:https://www.behaviortree.dev/
ros2 navigation:https://navigation.ros.org/
nav2_behavior_tree包是实现ros2的navigation2行为树的功能包,地址:https://github.com/ros-planning/navigation2/tree/main/nav2_behavior_tree
tick(调用)的工作原理
要在脑海中想象树的工作原理,请考虑下面的示例。
我们来重点关注一下nav2_behavior_tree功能包src下的主引擎节点behavior_tree_engine.cpp的代码:
注意:nav2_behavior_tree的行为树引擎behavior_tree_engine.cpp规则:每次都从主main中循环调用各个节点,每个节点根据运行情况,返回相应状态。
一个tick结束,如果main达到自己的success条件,可停止循环,返回成功状态,如果正在运行running可以继续tick(调用)。
如果tree是返回失败,则主循环结束,BehaviorTreeEngine::run返回failtrue。
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2020 Florian Gramss
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "nav2_behavior_tree/behavior_tree_engine.hpp"
#include
#include
#include
#include "rclcpp/rclcpp.hpp"
#include "behaviortree_cpp_v3/utils/shared_library.h"
namespace nav2_behavior_tree
{
BehaviorTreeEngine::BehaviorTreeEngine(const std::vector<std::string> & plugin_libraries)
{
BT::SharedLibrary loader;
for (const auto & p : plugin_libraries) {
factory_.registerFromPlugin(loader.getOSName(p));
}
}
BtStatus
BehaviorTreeEngine::run(
BT::Tree * tree,
std::function<void()> onLoop,
std::function<bool()> cancelRequested,
std::chrono::milliseconds loopTimeout)
{
rclcpp::WallRate loopRate(loopTimeout);
BT::NodeStatus result = BT::NodeStatus::RUNNING;
// Loop until something happens with ROS or the node completes
try {
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
if (cancelRequested()) {
tree->rootNode()->halt();
return BtStatus::CANCELED;
}
result = tree->tickRoot();
onLoop();
loopRate.sleep();
}
} catch (const std::exception & ex) {
RCLCPP_ERROR(
rclcpp::get_logger("BehaviorTreeEngine"),
"Behavior tree threw exception: %s. Exiting with failure.", ex.what());
return BtStatus::FAILED;
}
return (result == BT::NodeStatus::SUCCESS) ? BtStatus::SUCCEEDED : BtStatus::FAILED;
}
BT::Tree
BehaviorTreeEngine::createTreeFromText(
const std::string & xml_string,
BT::Blackboard::Ptr blackboard)
{
return factory_.createTreeFromText(xml_string, blackboard);
}
BT::Tree
BehaviorTreeEngine::createTreeFromFile(
const std::string & file_path,
BT::Blackboard::Ptr blackboard)
{
return factory_.createTreeFromFile(file_path, blackboard);
}
// In order to re-run a Behavior Tree, we must be able to reset all nodes to the initial state
void
BehaviorTreeEngine::haltAllActions(BT::TreeNode * root_node)
{
if (!root_node) {
return;
}
// this halt signal should propagate through the entire tree.
root_node->halt();
// but, just in case...
auto visitor = [](BT::TreeNode * node) {
if (node->status() == BT::NodeStatus::RUNNING) {
node->halt();
}
};
BT::applyRecursiveVisitor(root_node, visitor);
}
} // namespace nav2_behavior_tree
然后我们通过分析这个行为树:Navigate To Pose and Pause Near Goal-Obstacle(导航到目标位姿并具有接近障碍物暂停功能),这个是ros2导航比较经典的行为树,以下是他的树形图逻辑:
以上是ros常用的行为树示例。
表示为行为树xml文件内容如下:
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="6" name="NavigateRecovery">
<PipelineSequence name="NavigateWithReplanning">
<RateController hz="1.0">
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
RecoveryNode>
RateController>
<ReactiveSequence name="MonitorAndFollowPath">
<PathLongerOnApproach path="{path}" prox_len="3.0" length_factor="2.0">
<RetryUntilSuccessful num_attempts="1">
<SequenceStar name="CancelingControlAndWait">
<CancelControl name="ControlCancel"/>
<Wait wait_duration="5"/>
SequenceStar>
RetryUntilSuccessful>
PathLongerOnApproach>
<RecoveryNode number_of_retries="1" name="FollowPath">
<FollowPath path="{path}" controller_id="FollowPath"/>
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
RecoveryNode>
ReactiveSequence>
PipelineSequence>
<ReactiveFallback name="RecoveryFallback">
<GoalUpdated/>
<RoundRobin name="RecoveryActions">
<Sequence name="ClearingActions">
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
Sequence>
<Spin spin_dist="1.57"/>
<Wait wait_duration="5"/>
<BackUp backup_dist="0.30" backup_speed="0.05"/>
RoundRobin>
ReactiveFallback>
RecoveryNode>
BehaviorTree>
root>
然后我们主要分析每个语法的使用方法及作用。
1.recoveryNode 恢复节点。
RecoveryNode 是一个有两个子节点的控制流节点。
当且仅当第一个子节点返回 SUCCESS 时,它才会返回 SUCCESS。
只有当第一个子节点返回 FAILURE 时,才会执行第二个子节点。
如果第二个子节点成功,那么第一个子节点将被再次执行。
用户可以指定在返回 FAILURE 之前应该执行多少次恢复 *** 作。
在 nav2 中,RecoveryNode 包含在行为树中,用于在发生故障时执行恢复 *** 作。
使用恢复节点可能有一下几种情况:
1.第一个子节点调用后返回success,父节点返回success。
2.第一个子节点调用后返回running,父节点返回running不会调用第二个子节点。
3.第一个子节点调用后返回failtrue,RecoveryNode节点调用第二个子节点,
如果第二个子节点返回running,则父节点返回running,下一次tick还是调用第二个子节点。
如果第二个子节点返回success则直接调用第一个节点,如果第二个节点返回failtrue,则父节点返回failtrue。
例子:
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<RecoveryNode number_of_retries="1">
<ComputePathToPose/>
<ClearLocalCostmap/>
RecoveryNode>
BehaviorTree>
root>
实现代码:
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include
#include "nav2_behavior_tree/plugins/control/recovery_node.hpp"
namespace nav2_behavior_tree
{
RecoveryNode::RecoveryNode(
const std::string & name,
const BT::NodeConfiguration & conf)
: BT::ControlNode::ControlNode(name, conf),
current_child_idx_(0),
number_of_retries_(1),
retry_count_(0)
{
getInput("number_of_retries", number_of_retries_);
}
BT::NodeStatus RecoveryNode::tick()
{
const unsigned children_count = children_nodes_.size();
if (children_count != 2) {
throw BT::BehaviorTreeException("Recovery Node '" + name() + "' must only have 2 children.");
}
setStatus(BT::NodeStatus::RUNNING);
while (current_child_idx_ < children_count && retry_count_ <= number_of_retries_) {
TreeNode * child_node = children_nodes_[current_child_idx_];
const BT::NodeStatus child_status = child_node->executeTick();
if (current_child_idx_ == 0) {
switch (child_status) {
case BT::NodeStatus::SUCCESS:
{
// reset node and return success when first child returns success
halt();
return BT::NodeStatus::SUCCESS;
}
case BT::NodeStatus::FAILURE:
{
if (retry_count_ < number_of_retries_) {
// halt first child and tick second child in next iteration
ControlNode::haltChild(0);
current_child_idx_++;
break;
} else {
// reset node and return failure when max retries has been exceeded
halt();
return BT::NodeStatus::FAILURE;
}
}
case BT::NodeStatus::RUNNING:
{
return BT::NodeStatus::RUNNING;
}
default:
{
throw BT::LogicError("A child node must never return IDLE");
}
} // end switch
} else if (current_child_idx_ == 1) {
switch (child_status) {
case BT::NodeStatus::SUCCESS:
{
// halt second child, increment recovery count, and tick first child in next iteration
ControlNode::haltChild(1);
retry_count_++;
current_child_idx_--;
}
break;
case BT::NodeStatus::FAILURE:
{
// reset node and return failure if second child fails
halt();
return BT::NodeStatus::FAILURE;
}
case BT::NodeStatus::RUNNING:
{
return BT::NodeStatus::RUNNING;
}
default:
{
throw BT::LogicError("A child node must never return IDLE");
}
} // end switch
}
} // end while loop
// reset node and return failure
halt();
return BT::NodeStatus::FAILURE;
}
void RecoveryNode::halt()
{
ControlNode::halt();
retry_count_ = 0;
current_child_idx_ = 0;
}
} // namespace nav2_behavior_tree
#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::RecoveryNode>("RecoveryNode");
}
2.PipeLineSequence管道节点序列
初始状态Action_A,Action_B,Action_C三个节点都未被调用状态为初始idle,
当第一次调用Action_A的时候,假设Action_A节点反馈running状态,则父节点PipeLineSequence返回running。
主节点继续tick也不会调用Action_B和Action_C,直到Action_A返回success,则继续调用Action_B(注:如果任何一个子节点返回failtrue,则终止所有子节点动作,父节点返回failtrue)。
当Action_B返回running时,下一个tick会继续调用Action_A,无论A返回running或是success,都会继续调用Action_B(注:看代码
case BT::NodeStatus::RUNNING:
if (i >= last_child_ticked_))
然后判断Action_B状态。
如果此时Action_B,返回成功success,则继续调用Action_C。
如果Action_C返回running,则父节点继续调用Action_A及Action_B,及Action_C,这个过程并不返回,除非Action_C返回success,则父节点返回success并终止所有节点。
注:如果任何一个子节点返回failtrue,则终止所有子节点动作,父节点返回failtrue,具体看代码比较好理解逻辑。
主体代码:
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include
#include
#include
#include "nav2_behavior_tree/plugins/control/pipeline_sequence.hpp"
namespace nav2_behavior_tree
{
PipelineSequence::PipelineSequence(const std::string & name)
: BT::ControlNode(name, {})
{
}
PipelineSequence::PipelineSequence(
const std::string & name,
const BT::NodeConfiguration & config)
: BT::ControlNode(name, config)
{
}
BT::NodeStatus PipelineSequence::tick()
{
for (std::size_t i = 0; i < children_nodes_.size(); ++i) {
auto status = children_nodes_[i]->executeTick();
switch (status) {
case BT::NodeStatus::FAILURE:
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
return status;
case BT::NodeStatus::SUCCESS:
// do nothing and continue on to the next child. If it is the last child
// we'll exit the loop and hit the wrap-up code at the end of the method.
break;
case BT::NodeStatus::RUNNING:
if (i >= last_child_ticked_) {
last_child_ticked_ = i;
return status;
}
// else do nothing and continue on to the next child
break;
default:
std::stringstream error_msg;
error_msg << "Invalid node status. Received status " << status <<
"from child " << children_nodes_[i]->name();
throw std::runtime_error(error_msg.str());
}
}
// Wrap up.
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
return BT::NodeStatus::SUCCESS;
}
void PipelineSequence::halt()
{
BT::ControlNode::halt();
last_child_ticked_ = 0;
}
} // namespace nav2_behavior_tree
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::PipelineSequence>("PipelineSequence");
}
3.RoundRobin轮询控制节点
RoundRobin 控制节点以循环方式对其子节点进行调用,直到子节点返回SUCCESS,其中父节点也将返回SUCCESS。
如果所有子节点都返回FAILURE,那么父节点 RoundRobin 也会返回FAILURE。
循环过程中未成功或失败并不返回,直到循环结束,看代码更直接。
注:当前节点索引记忆current_child_idx_
xml行为树
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<RoundRobin>
<Action_A/>
<Action_B/>
<Action_C/>
RoundRobin>
BehaviorTree>
root>
c++代码
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include
#include "nav2_behavior_tree/plugins/control/round_robin_node.hpp"
namespace nav2_behavior_tree
{
RoundRobinNode::RoundRobinNode(const std::string & name)
: BT::ControlNode::ControlNode(name, {})
{
}
RoundRobinNode::RoundRobinNode(
const std::string & name,
const BT::NodeConfiguration & config)
: BT::ControlNode(name, config)
{
}
BT::NodeStatus RoundRobinNode::tick()
{
const auto num_children = children_nodes_.size();
setStatus(BT::NodeStatus::RUNNING);
while (num_failed_children_ < num_children) {
TreeNode * child_node = children_nodes_[current_child_idx_];
const BT::NodeStatus child_status = child_node->executeTick();
switch (child_status) {
case BT::NodeStatus::SUCCESS:
{
// Wrap around to the first child
if (++current_child_idx_ >= num_children) {
current_child_idx_ = 0;
}
num_failed_children_ = 0;
ControlNode::haltChildren();
return BT::NodeStatus::SUCCESS;
}
case BT::NodeStatus::FAILURE:
{
if (++current_child_idx_ >= num_children) {
current_child_idx_ = 0;
}
num_failed_children_++;
break;
}
case BT::NodeStatus::RUNNING:
{
return BT::NodeStatus::RUNNING;
}
default:
{
throw BT::LogicError("Invalid status return from BT node");
}
}
}
halt();
return BT::NodeStatus::FAILURE;
}
void RoundRobinNode::halt()
{
ControlNode::halt();
current_child_idx_ = 0;
num_failed_children_ = 0;
}
} // namespace nav2_behavior_tree
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::RoundRobinNode>("RoundRobin");
}
下一篇继续介绍其他指令
欢迎分享,转载请注明来源:内存溢出
评论列表(0条)