Skip to content

Commit

Permalink
update for BT.cpp master (#1714)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski committed May 9, 2020
1 parent 2113b6a commit 50b044a
Show file tree
Hide file tree
Showing 9 changed files with 12 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -49,13 +49,11 @@ class BehaviorTreeEngine
{
// this halt signal should propagate through the entire tree.
root_node->halt();
root_node->setStatus(BT::NodeStatus::IDLE);

// but, just in case...
auto visitor = [](BT::TreeNode * node) {
if (node->status() == BT::NodeStatus::RUNNING) {
node->halt();
node->setStatus(BT::NodeStatus::IDLE);
}
};
BT::applyRecursiveVisitor(root_node, visitor);
Expand Down
4 changes: 2 additions & 2 deletions nav2_behavior_tree/plugins/control/pipeline_sequence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ BT::NodeStatus PipelineSequence::tick()
auto status = children_nodes_[i]->executeTick();
switch (status) {
case BT::NodeStatus::FAILURE:
haltChildren(0);
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
return status;
break;
Expand All @@ -106,7 +106,7 @@ BT::NodeStatus PipelineSequence::tick()
}
}
// Wrap up.
haltChildren(0);
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
return BT::NodeStatus::SUCCESS;
}
Expand Down
4 changes: 2 additions & 2 deletions nav2_behavior_tree/plugins/control/recovery_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class RecoveryNode : public BT::ControlNode
current_child_idx_++;
break;
} else {
haltChildren(0);
ControlNode::haltChildren();
return BT::NodeStatus::FAILURE;
}
}
Expand All @@ -111,7 +111,7 @@ class RecoveryNode : public BT::ControlNode
{
retry_count_++;
current_child_idx_--;
haltChildren(1);
ControlNode::haltChildren();
}
break;

Expand Down
4 changes: 2 additions & 2 deletions nav2_behavior_tree/plugins/control/round_robin_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,11 @@ class RoundRobinNode : public BT::ControlNode
current_child_idx_ = 0;
}

haltChildren(0);
ControlNode::haltChildren();
return BT::NodeStatus::SUCCESS;

case BT::NodeStatus::FAILURE:
haltChildren(0);
ControlNode::haltChildren();
return BT::NodeStatus::FAILURE;

case BT::NodeStatus::RUNNING:
Expand Down
2 changes: 0 additions & 2 deletions nav2_behavior_tree/plugins/decorator/rate_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,13 +86,11 @@ inline BT::NodeStatus RateController::tick()
return BT::NodeStatus::RUNNING;

case BT::NodeStatus::SUCCESS:
child_node_->setStatus(BT::NodeStatus::IDLE);
start_ = std::chrono::high_resolution_clock::now(); // Reset the timer
return BT::NodeStatus::SUCCESS;

case BT::NodeStatus::FAILURE:
default:
child_node_->setStatus(BT::NodeStatus::IDLE);
return BT::NodeStatus::FAILURE;
}
}
Expand Down
4 changes: 2 additions & 2 deletions nav2_behavior_tree/src/behavior_tree_engine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,11 @@ BehaviorTreeEngine::run(
// Loop until something happens with ROS or the node completes
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
if (cancelRequested()) {
tree->root_node->halt();
tree->rootNode()->halt();
return BtStatus::CANCELED;
}

result = tree->root_node->executeTick();
result = tree->tickRoot();

onLoop();

Expand Down
4 changes: 2 additions & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
plugin_lib_names_.clear();
xml_string_.clear();
blackboard_.reset();
bt_->haltAllActions(tree_.root_node);
bt_->haltAllActions(tree_.rootNode());
bt_.reset();

RCLCPP_INFO(get_logger(), "Completed Cleaning up");
Expand Down Expand Up @@ -229,7 +229,7 @@ BtNavigator::navigateToPose()
nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling);
// Make sure that the Bt is not in a running state from a previous execution
// note: if all the ControlNodes are implemented correctly, this is not needed.
bt_->haltAllActions(tree_.root_node);
bt_->haltAllActions(tree_.rootNode());

switch (rc) {
case nav2_behavior_tree::BtStatus::SUCCEEDED:
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/src/ros_topic_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ namespace nav2_bt_navigator

RosTopicLogger::RosTopicLogger(
const rclcpp::Node::SharedPtr & ros_node, const BT::Tree & tree)
: StatusChangeLogger(tree.root_node), ros_node_(ros_node)
: StatusChangeLogger(tree.rootNode()), ros_node_(ros_node)
{
log_pub_ = ros_node_->create_publisher<nav2_msgs::msg::BehaviorTreeLog>(
"behavior_tree_log",
Expand Down
2 changes: 1 addition & 1 deletion tools/ros2_dependencies.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ repositories:
BehaviorTree.CPP:
type: git
url: https://github.com/BehaviorTree/BehaviorTree.CPP.git
version: ros2-3.1.1
version: master
angles:
type: git
url: https://github.com/ros/angles.git
Expand Down

0 comments on commit 50b044a

Please sign in to comment.