camera_buffer_pool.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * camera_aravis
4  *
5  * Copyright © 2022 Fraunhofer IOSB and contributors
6  *
7  * This library is free software; you can redistribute it and/or
8  * modify it under the terms of the GNU Library General Public
9  * License as published by the Free Software Foundation; either
10  * version 2 of the License, or (at your option) any later version.
11  *
12  * This library is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
15  * Library General Public License for more details.
16  *
17  * You should have received a copy of the GNU Library General Public
18  * License along with this library; if not, write to the
19  * Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
20  * Boston, MA 02110-1301, USA.
21  *
22  ****************************************************************************/
23 
24 #ifndef CAMERA_ARAVIS_CAMERA_BUFFER_POOL
25 #define CAMERA_ARAVIS_CAMERA_BUFFER_POOL
26 
27 extern "C" {
28 #include <arv.h>
29 }
30 
31 #include <ros/ros.h>
32 #include <boost/weak_ptr.hpp>
33 #include <boost/enable_shared_from_this.hpp>
34 #include <boost/bind.hpp>
35 #include <boost/bind/placeholders.hpp>
36 
37 #include <sensor_msgs/Image.h>
38 
39 #include <mutex>
40 #include <map>
41 #include <stack>
42 
43 namespace camera_aravis
44 {
45 
46 class CameraBufferPool : public boost::enable_shared_from_this<CameraBufferPool>
47 {
48 public:
50  typedef boost::weak_ptr<CameraBufferPool> WPtr;
51 
52  // Note: If the CameraBufferPool is destroyed, buffers will be deallocated. Therefor, make sure
53  // that the CameraBufferPool stays alive longer than the given stream object.
54  //
55  // stream: weakly managed pointer to the stream. Used to register all allocated buffers
56  // payload_size_bytes: size of a single buffer
57  // n_preallocated_buffers: number of initially allocated and registered buffers
58  CameraBufferPool(ArvStream *stream, size_t payload_size_bytes, size_t n_preallocated_buffers = 2);
59  virtual ~CameraBufferPool();
60 
61  // Get an image whose lifespan is administrated by this pool (but not registered to the camera).
62  sensor_msgs::ImagePtr getRecyclableImg();
63 
64  // Get the image message which wraps around the given ArvBuffer.
65  //
66  // If this buffer is not administrated by this CameraBufferPool,
67  // a new image message is allocated and the contents of the buffer
68  // are copied to it.
69  sensor_msgs::ImagePtr operator[](ArvBuffer *buffer);
70 
71  inline size_t getAllocatedSize() const
72  {
73  std::lock_guard<std::mutex> lock(mutex_);
74  return n_buffers_;
75  }
76 
77  inline size_t getUsedSize() const
78  {
79  std::lock_guard<std::mutex> lock(mutex_);
80  return used_buffers_.size();
81  }
82 
83  inline size_t getPayloadSize() const
84  {
85  return payload_size_bytes_;
86  }
87 
88  // Allocate new buffers which are wrapped by an image message and
89  // push them to the internal aravis stream.
90  void allocateBuffers(size_t n = 1);
91 
92 protected:
93  // Custom deleter for aravis buffer wrapping image messages, which
94  // either pushes the buffer back to the aravis stream cleans it up
95  // when the CameraBufferPool is gone.
96  static void reclaim(const WPtr &self, sensor_msgs::Image *p_img);
97 
98  // Push the buffer inside the given image back to the aravis stream,
99  // remember the corresponding image message.
100  void push(sensor_msgs::Image *p_img);
101 
102  ArvStream *stream_ = NULL;
103  size_t payload_size_bytes_ = 0;
104  size_t n_buffers_ = 0;
105 
106  std::map<const uint8_t*, sensor_msgs::ImagePtr> available_img_buffers_;
107  std::map<sensor_msgs::Image*, ArvBuffer*> used_buffers_;
108  std::stack<sensor_msgs::ImagePtr> dangling_imgs_;
109  mutable std::mutex mutex_;
110  Ptr self_;
111 };
112 
113 } /* namespace camera_aravis */
114 
115 #endif /* CAMERA_ARAVIS_CAMERA_BUFFER_POOL */
camera_aravis::CameraBufferPool::getUsedSize
size_t getUsedSize() const
Definition: camera_buffer_pool.h:119
camera_aravis::CameraBufferPool::getPayloadSize
size_t getPayloadSize() const
Definition: camera_buffer_pool.h:125
boost::shared_ptr< CameraBufferPool >
ros.h
camera_aravis::CameraBufferPool::dangling_imgs_
std::stack< sensor_msgs::ImagePtr > dangling_imgs_
Definition: camera_buffer_pool.h:150
camera_aravis::CameraBufferPool::getAllocatedSize
size_t getAllocatedSize() const
Definition: camera_buffer_pool.h:113
camera_aravis
Definition: camera_aravis_nodelet.h:81
camera_aravis::CameraBufferPool::~CameraBufferPool
virtual ~CameraBufferPool()
Definition: camera_buffer_pool.cpp:57
camera_aravis::CameraBufferPool::operator[]
sensor_msgs::ImagePtr operator[](ArvBuffer *buffer)
Definition: camera_buffer_pool.cpp:74
camera_aravis::CameraBufferPool::Ptr
boost::shared_ptr< CameraBufferPool > Ptr
Definition: camera_buffer_pool.h:91
camera_aravis::CameraBufferPool::stream_
ArvStream * stream_
Definition: camera_buffer_pool.h:144
camera_aravis::CameraBufferPool::reclaim
static void reclaim(const WPtr &self, sensor_msgs::Image *p_img)
Definition: camera_buffer_pool.cpp:128
camera_aravis::CameraBufferPool::n_buffers_
size_t n_buffers_
Definition: camera_buffer_pool.h:146
camera_aravis::CameraBufferPool::self_
Ptr self_
Definition: camera_buffer_pool.h:152
camera_aravis::CameraBufferPool::used_buffers_
std::map< sensor_msgs::Image *, ArvBuffer * > used_buffers_
Definition: camera_buffer_pool.h:149
camera_aravis::CameraBufferPool::getRecyclableImg
sensor_msgs::ImagePtr getRecyclableImg()
Definition: camera_buffer_pool.cpp:61
camera_aravis::CameraBufferPool::CameraBufferPool
CameraBufferPool(ArvStream *stream, size_t payload_size_bytes, size_t n_preallocated_buffers=2)
Definition: camera_buffer_pool.cpp:50
camera_aravis::CameraBufferPool::mutex_
std::mutex mutex_
Definition: camera_buffer_pool.h:151
camera_aravis::CameraBufferPool::payload_size_bytes_
size_t payload_size_bytes_
Definition: camera_buffer_pool.h:145
camera_aravis::CameraBufferPool::available_img_buffers_
std::map< const uint8_t *, sensor_msgs::ImagePtr > available_img_buffers_
Definition: camera_buffer_pool.h:148
camera_aravis::CameraBufferPool::push
void push(sensor_msgs::Image *p_img)
Definition: camera_buffer_pool.cpp:141
camera_aravis::CameraBufferPool::WPtr
boost::weak_ptr< CameraBufferPool > WPtr
Definition: camera_buffer_pool.h:92
camera_aravis::CameraBufferPool::allocateBuffers
void allocateBuffers(size_t n=1)
Definition: camera_buffer_pool.cpp:103


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