Skip to content

Commit 3fb012e

Browse files
authored
do not throw exception if trying to dequeue an empty intra-process buffer (#2061)
Signed-off-by: Alberto Soragna <[email protected]> Signed-off-by: Alberto Soragna <[email protected]>
1 parent 9c1c989 commit 3fb012e

File tree

2 files changed

+8
-3
lines changed

2 files changed

+8
-3
lines changed

rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,8 +86,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
8686
std::lock_guard<std::mutex> lock(mutex_);
8787

8888
if (!has_data_()) {
89-
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Calling dequeue on empty intra-process buffer");
90-
throw std::runtime_error("Calling dequeue on empty intra-process buffer");
89+
return BufferT();
9190
}
9291

9392
auto request = std::move(ring_buffer_[read_index_]);

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -109,8 +109,14 @@ class SubscriptionIntraProcess
109109

110110
if (any_callback_.use_take_shared_method()) {
111111
shared_msg = this->buffer_->consume_shared();
112+
if (!shared_msg) {
113+
return nullptr;
114+
}
112115
} else {
113116
unique_msg = this->buffer_->consume_unique();
117+
if (!unique_msg) {
118+
return nullptr;
119+
}
114120
}
115121
return std::static_pointer_cast<void>(
116122
std::make_shared<std::pair<ConstMessageSharedPtr, MessageUniquePtr>>(
@@ -138,7 +144,7 @@ class SubscriptionIntraProcess
138144
execute_impl(std::shared_ptr<void> & data)
139145
{
140146
if (!data) {
141-
throw std::runtime_error("'data' is empty");
147+
return;
142148
}
143149

144150
rmw_message_info_t msg_info;

0 commit comments

Comments
 (0)