@@ -57,14 +57,17 @@ class BtServiceNode : public BT::ActionNodeBase
5757 callback_group_executor_.add_callback_group (callback_group_, node_->get_node_base_interface ());
5858
5959 // Get the required items from the blackboard
60- bt_loop_duration_ =
60+ max_timeout_ =
6161 config ().blackboard ->template get <std::chrono::milliseconds>(" bt_loop_duration" );
6262 server_timeout_ =
6363 config ().blackboard ->template get <std::chrono::milliseconds>(" server_timeout" );
6464 getInput<std::chrono::milliseconds>(" server_timeout" , server_timeout_);
6565 wait_for_service_timeout_ =
6666 config ().blackboard ->template get <std::chrono::milliseconds>(" wait_for_service_timeout" );
6767
68+ // timeout should be less than bt_loop_duration to be able to finish the current tick
69+ max_timeout_ *= 0.5 ;
70+
6871 // Now that we have node_ to use, create the service client for this BT service
6972 getInput (" service_name" , service_name_);
7073 service_client_ = node_->create_client <ServiceT>(
@@ -189,7 +192,7 @@ class BtServiceNode : public BT::ActionNodeBase
189192 auto remaining = server_timeout_ - elapsed;
190193
191194 if (remaining > std::chrono::milliseconds (0 )) {
192- auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining;
195+ auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
193196
194197 rclcpp::FutureReturnCode rc;
195198 rc = callback_group_executor_.spin_until_future_complete (future_result_, timeout);
@@ -249,7 +252,7 @@ class BtServiceNode : public BT::ActionNodeBase
249252 std::chrono::milliseconds server_timeout_;
250253
251254 // The timeout value for BT loop execution
252- std::chrono::milliseconds bt_loop_duration_ ;
255+ std::chrono::milliseconds max_timeout_ ;
253256
254257 // The timeout value for waiting for a service to response
255258 std::chrono::milliseconds wait_for_service_timeout_;
0 commit comments