Skip to content

Commit

Permalink
Decide the output of BtServiceNode based on the service-response (#1615)
Browse files Browse the repository at this point in the history
- `BtServiceNode::check_future()` was created, to encapsulate the logic
where a the output of the BtServiceNode is computed.
- Inherited classes can overload this function according to the requirement
of the user
  • Loading branch information
atb033 authored Mar 27, 2020
1 parent 2214a04 commit 98faef5
Showing 1 changed file with 12 additions and 6 deletions.
18 changes: 12 additions & 6 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,19 @@ class BtServiceNode : public BT::SyncActionNode
{
on_tick();
auto future_result = service_client_->async_send_request(request_);
return check_future(future_result);
}

// Fill in service request with information if necessary
virtual void on_tick()
{
request_ = std::make_shared<typename ServiceT::Request>();
}

// Check the future and decide the status of Behaviortree
virtual BT::NodeStatus check_future(
std::shared_future<typename ServiceT::Response::SharedPtr> future_result)
{
rclcpp::executor::FutureReturnCode rc;
rc = rclcpp::spin_until_future_complete(
node_,
Expand All @@ -101,12 +113,6 @@ class BtServiceNode : public BT::SyncActionNode
return BT::NodeStatus::FAILURE;
}

// Fill in service request with information if necessary
virtual void on_tick()
{
request_ = std::make_shared<typename ServiceT::Request>();
}

// An opportunity to do something after
// a timeout waiting for a result that hasn't been received yet
virtual void on_wait_for_result()
Expand Down

0 comments on commit 98faef5

Please sign in to comment.