Skip to content
Snippets Groups Projects
Unverified Commit 054a6871 authored by Carl Delsey's avatar Carl Delsey Committed by GitHub
Browse files

Remove dead code (#1328)

parent f2697dab
No related branches found
No related tags found
No related merge requests found
......@@ -33,13 +33,6 @@ public:
BehaviorTreeEngine();
virtual ~BehaviorTreeEngine() {}
BtStatus run(
BT::Blackboard::Ptr & blackboard,
const std::string & behavior_tree_xml,
std::function<void()> onLoop,
std::function<bool()> cancelRequested,
std::chrono::milliseconds loopTimeout = std::chrono::milliseconds(10));
BtStatus run(
std::unique_ptr<BT::Tree> & tree,
std::function<void()> onLoop,
......
......@@ -63,37 +63,6 @@ BehaviorTreeEngine::BehaviorTreeEngine()
factory_.registerNodeType<nav2_behavior_tree::RecoveryNode>("RecoveryNode");
}
BtStatus
BehaviorTreeEngine::run(
BT::Blackboard::Ptr & blackboard,
const std::string & behavior_tree_xml,
std::function<void()> onLoop,
std::function<bool()> cancelRequested,
std::chrono::milliseconds loopTimeout)
{
// Parse the input XML and create the corresponding Behavior Tree
BT::Tree tree = buildTreeFromText(behavior_tree_xml, blackboard);
rclcpp::WallRate loopRate(loopTimeout);
BT::NodeStatus result = BT::NodeStatus::RUNNING;
// Loop until something happens with ROS or the node completes
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
if (cancelRequested()) {
tree.root_node->halt();
return BtStatus::CANCELED;
}
onLoop();
result = tree.root_node->executeTick();
loopRate.sleep();
}
return (result == BT::NodeStatus::SUCCESS) ? BtStatus::SUCCEEDED : BtStatus::FAILED;
}
BtStatus
BehaviorTreeEngine::run(
std::unique_ptr<BT::Tree> & tree,
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment