rgbd_image_buffer
Public Member Functions | Private Member Functions | Private Attributes | List of all members
rgbd::ImageBuffer Class Reference

The ImageBuffer class provides a buffer to synchronise rgbd images with sensor positions. Images are stored until they are removed from the buffer or until a certain amount of time has passed. More...

#include <image_buffer.h>

Public Member Functions

 ImageBuffer ()
 
void initialize (const std::string &topic, const std::string &root_frame="map", const float worker_thread_frequency=20)
 Configure the buffer. More...
 
bool nextImage (rgbd::ImageConstPtr &image, geo::Pose3D &sensor_pose)
 Returns the most recent combination of image and transform, provided it is different from the previous time the function was called. More...
 
bool waitForRecentImage (rgbd::ImageConstPtr &image, geo::Pose3D &sensor_pose, double timeout_sec, double check_rate)
 Blocks until a new image with transform is found. Returns false if no image or TF could be found within 'timeout_sec' seconds. But will always give it one try, both to get the image and to get TF. More...
 
bool waitForRecentImage (rgbd::ImageConstPtr &image, geo::Pose3D &sensor_pose, double timeout_sec, uint timeout_tries=25u)
 Blocks until a new image with transform is found. Returns false if no image or TF could be found within 'timeout_sec' seconds. But will always give it one try, both to get the image and to get TF. More...
 
 ~ImageBuffer ()
 

Private Member Functions

bool getMostRecentImageTF ()
 Iterates over the buffer and tries to get TF for the most recent image. Deletes image and all older images when succesful or when image is too old from the buffer. More...
 
void workerThreadFunc (const float frequency=20)
 Calls ImageBuffer::getMostRecentImageTF on the specified frequency. More...
 

Private Attributes

ros::CallbackQueue cb_queue_
 
std::forward_list< rgbd::ImageConstPtrimage_buffer_
 Newer images should be pushed on the front. This will result in the front being the most recent and the back being the oldest. More...
 
std::pair< rgbd::ImageConstPtr, geo::Pose3Drecent_image_
 
std::mutex recent_image_mutex_
 For protecting ImageBuffer::recent_image_. More...
 
std::unique_ptr< rgbd::Clientrgbd_client_
 
std::string root_frame_
 
bool shutdown_
 
tf2_ros::Buffer tf_buffer_
 
std::unique_ptr< tf2_ros::TransformListener > tf_listener_
 
std::unique_ptr< std::threadworker_thread_ptr_
 

Detailed Description

The ImageBuffer class provides a buffer to synchronise rgbd images with sensor positions. Images are stored until they are removed from the buffer or until a certain amount of time has passed.

Definition at line 31 of file image_buffer.h.

Constructor & Destructor Documentation

◆ ImageBuffer()

rgbd::ImageBuffer::ImageBuffer ( )

Definition at line 20 of file image_buffer.cpp.

◆ ~ImageBuffer()

rgbd::ImageBuffer::~ImageBuffer ( )

Definition at line 26 of file image_buffer.cpp.

Member Function Documentation

◆ getMostRecentImageTF()

bool rgbd::ImageBuffer::getMostRecentImageTF ( )
private

Iterates over the buffer and tries to get TF for the most recent image. Deletes image and all older images when succesful or when image is too old from the buffer.

Returns
Indicates whether the most recent image has been updated

Definition at line 157 of file image_buffer.cpp.

◆ initialize()

void rgbd::ImageBuffer::initialize ( const std::string topic,
const std::string root_frame = "map",
const float  worker_thread_frequency = 20 
)

Configure the buffer.

Parameters
topicros topic on which the rgbd images are published
root_frameroot frame to calculate sensor pose relative to (default: map)
worker_thread_frequencyfrequency at which the worker thread updates the most recent image (default: 20)

Definition at line 35 of file image_buffer.cpp.

◆ nextImage()

bool rgbd::ImageBuffer::nextImage ( rgbd::ImageConstPtr image,
geo::Pose3D sensor_pose 
)

Returns the most recent combination of image and transform, provided it is different from the previous time the function was called.

Parameters
[out]imagergbd image to write the next image to. Iff a next image is found
[out]sensor_posewill be filled with the sensor pose corresponding to the next image. Iff a next image is found
Returns
whether or not a novel image is available

Definition at line 138 of file image_buffer.cpp.

◆ waitForRecentImage() [1/2]

bool rgbd::ImageBuffer::waitForRecentImage ( rgbd::ImageConstPtr image,
geo::Pose3D sensor_pose,
double  timeout_sec,
double  check_rate 
)

Blocks until a new image with transform is found. Returns false if no image or TF could be found within 'timeout_sec' seconds. But will always give it one try, both to get the image and to get TF.

Parameters
[out]imagergbd image to write the next image to. Iff a next image is found
[out]sensor_posewill be filled with the sensor pose corresponding to the next image. Iff a next image is found
[in]timeout_secmaximum duration to block.
[in]check_rateCheck for a new image on this frequency. In case =0, set to 10 Hz
Returns
whether or not a next image was available within the timeout duration.

Definition at line 52 of file image_buffer.cpp.

◆ waitForRecentImage() [2/2]

bool rgbd::ImageBuffer::waitForRecentImage ( rgbd::ImageConstPtr image,
geo::Pose3D sensor_pose,
double  timeout_sec,
uint  timeout_tries = 25u 
)

Blocks until a new image with transform is found. Returns false if no image or TF could be found within 'timeout_sec' seconds. But will always give it one try, both to get the image and to get TF.

Parameters
[out]imagergbd image to write the next image to. Iff a next image is found
[out]sensor_posewill be filled with the sensor pose corresponding to the next image. Iff a next image is found
[in]timeout_secmaximum duration to block.
[in,opt]timeout_tries number of tries to check for a new image. In case =0, set to 25 tries
Returns
whether or not a next image was available within the timeout duration.

Definition at line 124 of file image_buffer.cpp.

◆ workerThreadFunc()

void rgbd::ImageBuffer::workerThreadFunc ( const float  frequency = 20)
private

Calls ImageBuffer::getMostRecentImageTF on the specified frequency.

Parameters
frequencyFrequency for checking new images.

Definition at line 250 of file image_buffer.cpp.

Member Data Documentation

◆ cb_queue_

ros::CallbackQueue rgbd::ImageBuffer::cb_queue_
private

Definition at line 92 of file image_buffer.h.

◆ image_buffer_

std::forward_list<rgbd::ImageConstPtr> rgbd::ImageBuffer::image_buffer_
private

Newer images should be pushed on the front. This will result in the front being the most recent and the back being the oldest.

Definition at line 90 of file image_buffer.h.

◆ recent_image_

std::pair<rgbd::ImageConstPtr, geo::Pose3D> rgbd::ImageBuffer::recent_image_
private

Definition at line 94 of file image_buffer.h.

◆ recent_image_mutex_

std::mutex rgbd::ImageBuffer::recent_image_mutex_
private

For protecting ImageBuffer::recent_image_.

Definition at line 98 of file image_buffer.h.

◆ rgbd_client_

std::unique_ptr<rgbd::Client> rgbd::ImageBuffer::rgbd_client_
private

Definition at line 82 of file image_buffer.h.

◆ root_frame_

std::string rgbd::ImageBuffer::root_frame_
private

Definition at line 80 of file image_buffer.h.

◆ shutdown_

bool rgbd::ImageBuffer::shutdown_
private

Definition at line 100 of file image_buffer.h.

◆ tf_buffer_

tf2_ros::Buffer rgbd::ImageBuffer::tf_buffer_
private

Definition at line 84 of file image_buffer.h.

◆ tf_listener_

std::unique_ptr<tf2_ros::TransformListener> rgbd::ImageBuffer::tf_listener_
private

Definition at line 85 of file image_buffer.h.

◆ worker_thread_ptr_

std::unique_ptr<std::thread> rgbd::ImageBuffer::worker_thread_ptr_
private

Definition at line 99 of file image_buffer.h.


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