Program Listing for File concurrent_queue.hpp

Return to documentation for file (include/camera_aravis2/concurrent_queue.hpp)

// Copyright (c) 2024 Fraunhofer IOSB and contributors
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
//    * Redistributions of source code must retain the above copyright
//      notice, this list of conditions and the following disclaimer.
//
//    * Redistributions in binary form must reproduce the above copyright
//      notice, this list of conditions and the following disclaimer in the
//      documentation and/or other materials provided with the distribution.
//
//    * Neither the name of the Fraunhofer IOSB nor the names of its
//      contributors may be used to endorse or promote products derived from
//      this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef CAMERA_ARAVIS2__CONCURRENT_QUEUE_HPP_
#define CAMERA_ARAVIS2__CONCURRENT_QUEUE_HPP_

// Std
#include <condition_variable>
#include <mutex>
#include <queue>

namespace camera_aravis2
{

template <typename T>
class ConcurrentQueue
{
    //--- METHOD DECLARATION ---//

  public:
    [[nodiscard]] bool empty() const noexcept
    {
        std::lock_guard<std::mutex> lck(mtx_);
        return queue_.empty();
    }

    [[nodiscard]] size_t size() const noexcept
    {
        std::lock_guard<std::mutex> lck(mtx_);
        return queue_.size();
    }

    void push(const T& input) noexcept
    {
        {
            std::lock_guard<std::mutex> lck(mtx_);
            queue_.push(input);
        }
        cond_.notify_one();
    }

    void pop(T& output) noexcept
    {
        std::unique_lock<std::mutex> lck(mtx_);
        cond_.wait(lck, [this]
                   { return !queue_.empty(); });
        output = queue_.front();
        queue_.pop();
    }

    //--- MEMBER DECLARATION ---//

  private:
    std::queue<T> queue_;

    std::condition_variable cond_;

    mutable std::mutex mtx_;
};

}  // namespace camera_aravis2

#endif  // CAMERA_ARAVIS2__CONCURRENT_QUEUE_HPP_