Skip to content

Commit

Permalink
Use correct timeout when checking future (ros-navigation#3087)
Browse files Browse the repository at this point in the history
  • Loading branch information
samiamlabs authored and Joshua Wallace committed Dec 14, 2022
1 parent ffa0061 commit ee06ded
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class BtServiceNode : public BT::ActionNodeBase
auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining;

rclcpp::FutureReturnCode rc;
rc = callback_group_executor_.spin_until_future_complete(future_result_, server_timeout_);
rc = callback_group_executor_.spin_until_future_complete(future_result_, timeout);
if (rc == rclcpp::FutureReturnCode::SUCCESS) {
request_sent_ = false;
BT::NodeStatus status = on_completion(future_result_.get());
Expand Down

0 comments on commit ee06ded

Please sign in to comment.