Skip to content

Commit

Permalink
Switch to std::optional<T> take()
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard committed Nov 26, 2024
1 parent aa29d41 commit 939eca3
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define ROSBAG2_TRANSPORT__LOCKED_PRIORITY_QUEUE_HPP_

#include <mutex>
#include <optional>
#include <queue>

#include "rcpputils/thread_safety_annotations.hpp"
Expand All @@ -32,10 +33,8 @@ class LockedPriorityQueue
public:
/// \brief Constructor.
/// \param compare the comparator object
/// \param empty_element the element to return when trying to take with an empty queue
LockedPriorityQueue(const Compare & compare, const T & empty_element)
: queue_(compare),
empty_element_{empty_element}
LockedPriorityQueue(const Compare & compare)
: queue_(compare)
{}

LockedPriorityQueue() = delete;
Expand Down Expand Up @@ -85,12 +84,12 @@ class LockedPriorityQueue
}

/// \brief Try to take the top element from the queue.
/// \return the top element, or `empty_element` if the queue is empty
T take()
/// \return the top element, or `std::nullopt` if the queue is empty
std::optional<T> take()
{
rcpputils::unique_lock<std::mutex> lk(queue_mutex_);
if (queue_.empty()) {
return empty_element_;
return std::nullopt;
}
const T e = queue_.top();
queue_.pop();
Expand All @@ -100,7 +99,6 @@ class LockedPriorityQueue
private:
mutable std::mutex queue_mutex_;
std::priority_queue<T, Container, Compare> queue_ RCPPUTILS_TSA_GUARDED_BY(queue_mutex_);
const T empty_element_;
};

#endif // ROSBAG2_TRANSPORT__LOCKED_PRIORITY_QUEUE_HPP_
5 changes: 2 additions & 3 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,8 +388,7 @@ PlayerImpl::PlayerImpl(
: input_bags_(std::move(input_bags)),
owner_(owner),
play_options_(play_options),
// Return empty shared_ptr when taking from an empty queue
message_queue_(BagMessageRecvTimestampComparator{}, nullptr),
message_queue_(BagMessageRecvTimestampComparator{}),
keyboard_handler_(std::move(keyboard_handler)),
player_service_client_manager_(std::make_shared<PlayerServiceClientManager>())
{
Expand Down Expand Up @@ -698,7 +697,7 @@ rosbag2_storage::SerializedBagMessageSharedPtr PlayerImpl::take_next_message_fro
std::this_thread::sleep_for(std::chrono::microseconds(100));
}
// Note: this only returns nullptr if no more messages
return message_queue_.take();
return message_queue_.take().value_or(nullptr);
}

bool PlayerImpl::play_next()
Expand Down

0 comments on commit 939eca3

Please sign in to comment.