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>
|
| 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 () |
|
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.
◆ ImageBuffer()
rgbd::ImageBuffer::ImageBuffer |
( |
| ) |
|
◆ ~ImageBuffer()
rgbd::ImageBuffer::~ImageBuffer |
( |
| ) |
|
◆ 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
-
topic | ros topic on which the rgbd images are published |
root_frame | root frame to calculate sensor pose relative to (default: map) |
worker_thread_frequency | frequency at which the worker thread updates the most recent image (default: 20) |
Definition at line 35 of file image_buffer.cpp.
◆ nextImage()
Returns the most recent combination of image and transform, provided it is different from the previous time the function was called.
- Parameters
-
[out] | image | rgbd image to write the next image to. Iff a next image is found |
[out] | sensor_pose | will 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]
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] | image | rgbd image to write the next image to. Iff a next image is found |
[out] | sensor_pose | will be filled with the sensor pose corresponding to the next image. Iff a next image is found |
[in] | timeout_sec | maximum duration to block. |
[in] | check_rate | Check 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]
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] | image | rgbd image to write the next image to. Iff a next image is found |
[out] | sensor_pose | will be filled with the sensor pose corresponding to the next image. Iff a next image is found |
[in] | timeout_sec | maximum 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 |
◆ cb_queue_
ros::CallbackQueue rgbd::ImageBuffer::cb_queue_ |
|
private |
◆ image_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.
Definition at line 90 of file image_buffer.h.
◆ recent_image_
◆ recent_image_mutex_
◆ rgbd_client_
◆ root_frame_
◆ shutdown_
bool rgbd::ImageBuffer::shutdown_ |
|
private |
◆ tf_buffer_
tf2_ros::Buffer rgbd::ImageBuffer::tf_buffer_ |
|
private |
◆ tf_listener_
std::unique_ptr<tf2_ros::TransformListener> rgbd::ImageBuffer::tf_listener_ |
|
private |
◆ worker_thread_ptr_
The documentation for this class was generated from the following files: