Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds onLoopBeforeTick callback to BT::TreeExecutionServer. #101

Open
wants to merge 1 commit into
base: humble
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,21 @@ class TreeExecutionServer
virtual void registerNodesIntoFactory(BT::BehaviorTreeFactory& factory)
{}

/**
* @brief onLoopBeforeTick invoked at each loop, before tree.tickOnce().
* It can be overridden to avoid ticking the tree without blocking the
* rest of the execute loop.
*
* Consider whether it's better to inject a preTickCallback to the root node
* or another node of the behavior tree.
*
* @return False to skip the tick.
*/
virtual bool onLoopBeforeTick()
{
return true;
}

/**
* @brief onLoopAfterTick invoked at each loop, after tree.tickOnce().
* If it returns a valid NodeStatus, the tree will stop and return that status.
Expand Down
31 changes: 17 additions & 14 deletions behaviortree_ros2/src/tree_execution_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,21 +222,24 @@ void TreeExecutionServer::execute(
return;
}

// tick the tree once and publish the action feedback
status = p_->tree.tickExactlyOnce();

if(const auto res = onLoopAfterTick(status); res.has_value())
{
stop_action(res.value(), "Action Server aborted by onLoopAfterTick()");
goal_handle->abort(action_result);
return;
}

if(const auto res = onLoopFeedback(); res.has_value())
if(onLoopBeforeTick())
{
auto feedback = std::make_shared<ExecuteTree::Feedback>();
feedback->message = res.value();
goal_handle->publish_feedback(feedback);
// tick the tree once and publish the action feedback
status = p_->tree.tickExactlyOnce();

if(const auto res = onLoopAfterTick(status); res.has_value())
{
stop_action(res.value(), "Action Server aborted by onLoopAfterTick()");
goal_handle->abort(action_result);
return;
}

if(const auto res = onLoopFeedback(); res.has_value())
{
auto feedback = std::make_shared<ExecuteTree::Feedback>();
feedback->message = res.value();
goal_handle->publish_feedback(feedback);
}
}

const auto now = std::chrono::steady_clock::now();
Expand Down