Skip to content

Commit

Permalink
Add recursive mutexs to ring buffer to avoid race conditions
Browse files Browse the repository at this point in the history
  • Loading branch information
audrow committed Jul 1, 2020
1 parent a8cd936 commit df1dd39
Showing 1 changed file with 7 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

void enqueue(BufferT request)
{
std::lock_guard<std::mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(recursive_mutex_);

write_index_ = next(write_index_);
ring_buffer_[write_index_] = std::move(request);
Expand All @@ -71,7 +71,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

BufferT dequeue()
{
std::lock_guard<std::mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(recursive_mutex_);

if (!has_data()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Calling dequeue on empty intra-process buffer");
Expand All @@ -88,16 +88,19 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

inline size_t next(size_t val)
{
std::lock_guard<std::recursive_mutex> lock(recursive_mutex_);
return (val + 1) % capacity_;
}

inline bool has_data() const
{
std::lock_guard<std::recursive_mutex> lock(recursive_mutex_);
return size_ != 0;
}

inline bool is_full()
inline bool is_full() const
{
std::lock_guard<std::recursive_mutex> lock(recursive_mutex_);
return size_ == capacity_;
}

Expand All @@ -112,7 +115,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
size_t read_index_;
size_t size_;

std::mutex mutex_;
mutable std::recursive_mutex recursive_mutex_;
};

} // namespace buffers
Expand Down

0 comments on commit df1dd39

Please sign in to comment.