Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
camera_aravis::CameraBufferPool Class Reference

#include <camera_buffer_pool.h>

Inheritance diagram for camera_aravis::CameraBufferPool:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< CameraBufferPoolPtr
 
typedef boost::weak_ptr< CameraBufferPoolWPtr
 

Public Member Functions

void allocateBuffers (size_t n=1)
 
 CameraBufferPool (ArvStream *stream, size_t payload_size_bytes, size_t n_preallocated_buffers=2)
 
size_t getAllocatedSize () const
 
size_t getPayloadSize () const
 
sensor_msgs::ImagePtr getRecyclableImg ()
 
size_t getUsedSize () const
 
sensor_msgs::ImagePtr operator[] (ArvBuffer *buffer)
 
virtual ~CameraBufferPool ()
 

Protected Member Functions

void push (sensor_msgs::Image *p_img)
 

Static Protected Member Functions

static void reclaim (const WPtr &self, sensor_msgs::Image *p_img)
 

Protected Attributes

std::map< const uint8_t *, sensor_msgs::ImagePtr > available_img_buffers_
 
std::stack< sensor_msgs::ImagePtr > dangling_imgs_
 
std::mutex mutex_
 
size_t n_buffers_ = 0
 
size_t payload_size_bytes_ = 0
 
Ptr self_
 
ArvStream * stream_ = NULL
 
std::map< sensor_msgs::Image *, ArvBuffer * > used_buffers_
 

Detailed Description

Definition at line 67 of file camera_buffer_pool.h.

Member Typedef Documentation

◆ Ptr

Definition at line 91 of file camera_buffer_pool.h.

◆ WPtr

Definition at line 92 of file camera_buffer_pool.h.

Constructor & Destructor Documentation

◆ CameraBufferPool()

camera_aravis::CameraBufferPool::CameraBufferPool ( ArvStream *  stream,
size_t  payload_size_bytes,
size_t  n_preallocated_buffers = 2 
)

Definition at line 50 of file camera_buffer_pool.cpp.

◆ ~CameraBufferPool()

camera_aravis::CameraBufferPool::~CameraBufferPool ( )
virtual

Definition at line 57 of file camera_buffer_pool.cpp.

Member Function Documentation

◆ allocateBuffers()

void camera_aravis::CameraBufferPool::allocateBuffers ( size_t  n = 1)

Definition at line 103 of file camera_buffer_pool.cpp.

◆ getAllocatedSize()

size_t camera_aravis::CameraBufferPool::getAllocatedSize ( ) const
inline

Definition at line 113 of file camera_buffer_pool.h.

◆ getPayloadSize()

size_t camera_aravis::CameraBufferPool::getPayloadSize ( ) const
inline

Definition at line 125 of file camera_buffer_pool.h.

◆ getRecyclableImg()

sensor_msgs::ImagePtr camera_aravis::CameraBufferPool::getRecyclableImg ( )

Definition at line 61 of file camera_buffer_pool.cpp.

◆ getUsedSize()

size_t camera_aravis::CameraBufferPool::getUsedSize ( ) const
inline

Definition at line 119 of file camera_buffer_pool.h.

◆ operator[]()

sensor_msgs::ImagePtr camera_aravis::CameraBufferPool::operator[] ( ArvBuffer *  buffer)

Definition at line 74 of file camera_buffer_pool.cpp.

◆ push()

void camera_aravis::CameraBufferPool::push ( sensor_msgs::Image *  p_img)
protected

Definition at line 141 of file camera_buffer_pool.cpp.

◆ reclaim()

void camera_aravis::CameraBufferPool::reclaim ( const WPtr self,
sensor_msgs::Image *  p_img 
)
staticprotected

Definition at line 128 of file camera_buffer_pool.cpp.

Member Data Documentation

◆ available_img_buffers_

std::map<const uint8_t*, sensor_msgs::ImagePtr> camera_aravis::CameraBufferPool::available_img_buffers_
protected

Definition at line 148 of file camera_buffer_pool.h.

◆ dangling_imgs_

std::stack<sensor_msgs::ImagePtr> camera_aravis::CameraBufferPool::dangling_imgs_
protected

Definition at line 150 of file camera_buffer_pool.h.

◆ mutex_

std::mutex camera_aravis::CameraBufferPool::mutex_
mutableprotected

Definition at line 151 of file camera_buffer_pool.h.

◆ n_buffers_

size_t camera_aravis::CameraBufferPool::n_buffers_ = 0
protected

Definition at line 146 of file camera_buffer_pool.h.

◆ payload_size_bytes_

size_t camera_aravis::CameraBufferPool::payload_size_bytes_ = 0
protected

Definition at line 145 of file camera_buffer_pool.h.

◆ self_

Ptr camera_aravis::CameraBufferPool::self_
protected

Definition at line 152 of file camera_buffer_pool.h.

◆ stream_

ArvStream* camera_aravis::CameraBufferPool::stream_ = NULL
protected

Definition at line 144 of file camera_buffer_pool.h.

◆ used_buffers_

std::map<sensor_msgs::Image*, ArvBuffer*> camera_aravis::CameraBufferPool::used_buffers_
protected

Definition at line 149 of file camera_buffer_pool.h.


The documentation for this class was generated from the following files:


camera_aravis
Author(s): Boitumelo Ruf, Fraunhofer IOSB , Dominik Kleiser, Fraunhofer IOSB , Dominik A. Klein, Fraunhofer FKIE , Steve Safarik, Straw Lab , Andrew Straw, Straw Lab , Floris van Breugel, van Breugel Lab
autogenerated on Wed Mar 13 2024 02:23:00