cartographer源码分析(11)-common-blocking_queue.h

源码可在https://github.com/learnmoreonce/SLAM 下载


文件:common/blocking_queue.h


#ifndef CARTOGRAPHER_COMMON_BLOCKING_QUEUE_H_
#define CARTOGRAPHER_COMMON_BLOCKING_QUEUE_H_

#include <cstddef>
#include <deque>
#include <memory>

#include "cartographer/common/mutex.h"
#include "cartographer/common/port.h"
#include "cartographer/common/time.h"
#include "glog/logging.h"
/*
 * BlockingQueue是线程安全的阻塞队列,(生产者消费者模式)
 * 不可拷贝不可赋值
 * 构造函数初始化队列大小,kInfiniteQueueSize=0默认不限制容量。queue_size限制容量:通过条件变量做到.
 * Push()添加元素,容量不够时,阻塞等待
 * Pop()删除元素,没有元素时,阻塞等待
 * Peek()返回下一个应该弹出的元素
 * PushWithTimeout(),添加元素,若超时则返回false
 * PopWithTimeout(),删除元素,若超时则返回false
 *
 * */
namespace cartographer {
namespace common {

// A thread-safe blocking queue that is useful for producer/consumer patterns.
// 'T' must be movable.
template <typename T>
class BlockingQueue {
 public:
  static constexpr size_t kInfiniteQueueSize = 0;

  // Constructs a blocking queue with infinite queue size.
  BlockingQueue() : BlockingQueue(kInfiniteQueueSize) {} //默认不限制容量

  BlockingQueue(const BlockingQueue&) = delete;
  BlockingQueue& operator=(const BlockingQueue&) = delete;

  // Constructs a blocking queue with a size of 'queue_size'.限制容量
  explicit BlockingQueue(const size_t queue_size) : queue_size_(queue_size) {}

  // Pushes a value onto the queue. Blocks if the queue is full.
  void Push(T t) {
    MutexLocker lock(&mutex_);//加锁
    lock.Await([this]() REQUIRES(mutex_) { return QueueNotFullCondition(); });//队列未满才能push
    deque_.push_back(std::move(t)); 
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值