diff --git a/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp b/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp index c01240b429..245d417d86 100644 --- a/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp +++ b/rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp @@ -86,8 +86,7 @@ class RingBufferImplementation : public BufferImplementationBase std::lock_guard lock(mutex_); if (!has_data_()) { - RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Calling dequeue on empty intra-process buffer"); - throw std::runtime_error("Calling dequeue on empty intra-process buffer"); + return BufferT(); } auto request = std::move(ring_buffer_[read_index_]); diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp index 803d940086..91ea91a7c3 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp @@ -109,8 +109,14 @@ class SubscriptionIntraProcess if (any_callback_.use_take_shared_method()) { shared_msg = this->buffer_->consume_shared(); + if (!shared_msg) { + return nullptr; + } } else { unique_msg = this->buffer_->consume_unique(); + if (!unique_msg) { + return nullptr; + } } return std::static_pointer_cast( std::make_shared>( @@ -138,7 +144,7 @@ class SubscriptionIntraProcess execute_impl(std::shared_ptr & data) { if (!data) { - throw std::runtime_error("'data' is empty"); + return; } rmw_message_info_t msg_info;