@@ -344,7 +344,16 @@ ServerBase::execute_goal_request_received(std::shared_ptr<void> & data)
344344 }
345345
346346 if (RCL_RET_OK != ret) {
347- rclcpp::exceptions::throw_from_rcl_error (ret);
347+ if (ret == RCL_RET_TIMEOUT) {
348+ RCLCPP_WARN (
349+ pimpl_->logger_ ,
350+ " Failed to send goal response %s (timeout): %s" ,
351+ to_string (uuid).c_str (), rcl_get_error_string ().str );
352+ rcl_reset_error ();
353+ return ;
354+ } else {
355+ rclcpp::exceptions::throw_from_rcl_error (ret);
356+ }
348357 }
349358
350359 const auto status = response_pair.first ;
@@ -483,6 +492,15 @@ ServerBase::execute_cancel_request_received(std::shared_ptr<void> & data)
483492 pimpl_->action_server_ .get (), &request_header, response.get ());
484493 }
485494
495+ if (ret == RCL_RET_TIMEOUT) {
496+ GoalUUID uuid = request->goal_info .goal_id .uuid ;
497+ RCLCPP_WARN (
498+ pimpl_->logger_ ,
499+ " Failed to send cancel response %s (timeout): %s" ,
500+ to_string (uuid).c_str (), rcl_get_error_string ().str );
501+ rcl_reset_error ();
502+ return ;
503+ }
486504 if (RCL_RET_OK != ret) {
487505 rclcpp::exceptions::throw_from_rcl_error (ret);
488506 }
@@ -538,6 +556,14 @@ ServerBase::execute_result_request_received(std::shared_ptr<void> & data)
538556 std::lock_guard<std::recursive_mutex> lock (pimpl_->action_server_reentrant_mutex_ );
539557 rcl_ret_t rcl_ret = rcl_action_send_result_response (
540558 pimpl_->action_server_ .get (), &request_header, result_response.get ());
559+ if (rcl_ret == RCL_RET_TIMEOUT) {
560+ RCLCPP_WARN (
561+ pimpl_->logger_ ,
562+ " Failed to send result response %s (timeout): %s" ,
563+ to_string (uuid).c_str (), rcl_get_error_string ().str );
564+ rcl_reset_error ();
565+ return ;
566+ }
541567 if (RCL_RET_OK != rcl_ret) {
542568 rclcpp::exceptions::throw_from_rcl_error (rcl_ret);
543569 }
@@ -671,7 +697,13 @@ ServerBase::publish_result(const GoalUUID & uuid, std::shared_ptr<void> result_m
671697 for (auto & request_header : iter->second ) {
672698 rcl_ret_t ret = rcl_action_send_result_response (
673699 pimpl_->action_server_ .get (), &request_header, result_msg.get ());
674- if (RCL_RET_OK != ret) {
700+ if (ret == RCL_RET_TIMEOUT) {
701+ RCLCPP_WARN (
702+ pimpl_->logger_ ,
703+ " Failed to send result response %s (timeout): %s" ,
704+ to_string (uuid).c_str (), rcl_get_error_string ().str );
705+ rcl_reset_error ();
706+ } else if (RCL_RET_OK != ret) {
675707 rclcpp::exceptions::throw_from_rcl_error (ret);
676708 }
677709 }
0 commit comments