Public Member Functions | Private Attributes | List of all members
rcgccam::ImageList Class Reference

#include <imagelist.h>

Public Member Functions

sensor_msgs::ImagePtr add (const sensor_msgs::ImagePtr &image)
 Adds the given image to the internal list. More...
 
sensor_msgs::ImagePtr find (const ros::Time &timestamp) const
 Returns the oldest image that has a timestamp within the tolerance of the given timestamp. More...
 
 ImageList ()
 Create an image list. More...
 
int removeOld (const ros::Time &timestamp)
 Remove all images that have a timestamp that is older or equal than the given timestamp. More...
 
void setSize (size_t maxsize)
 Set maximum size of the list. More...
 
void setTolerance (uint64_t tolerance)
 Set tolerance for finding corresponding timestamps. More...
 

Private Attributes

std::vector< sensor_msgs::ImagePtr > list_
 
size_t maxsize_
 
uint64_t tolerance_
 

Detailed Description

Definition at line 44 of file imagelist.h.

Constructor & Destructor Documentation

◆ ImageList()

rcgccam::ImageList::ImageList ( )

Create an image list.

Definition at line 42 of file imagelist.cc.

Member Function Documentation

◆ add()

sensor_msgs::ImagePtr rcgccam::ImageList::add ( const sensor_msgs::ImagePtr &  image)

Adds the given image to the internal list.

If the maximum number of elements is exceeded, then the oldest image will be dropped.

Parameters
imageImage to be added.
Returns
Dropped image, null pointer if no image is dropped.

Definition at line 57 of file imagelist.cc.

◆ find()

sensor_msgs::ImagePtr rcgccam::ImageList::find ( const ros::Time timestamp) const

Returns the oldest image that has a timestamp within the tolerance of the given timestamp.

If the image cannot be found, then a nullptr is returned.

Parameters
timestampTimestamp.
toleranceMaximum tolarance added or subtracted to the timestamp.
Returns
Pointer to image or 0.

Definition at line 93 of file imagelist.cc.

◆ removeOld()

int rcgccam::ImageList::removeOld ( const ros::Time timestamp)

Remove all images that have a timestamp that is older or equal than the given timestamp.

Parameters
timestampTimestamp.
Returns
Number of removed images.

Definition at line 72 of file imagelist.cc.

◆ setSize()

void rcgccam::ImageList::setSize ( size_t  maxsize)

Set maximum size of the list.

Parameters
maxsizeMaximum number of elements that the list can hold. The default is 25.

Definition at line 47 of file imagelist.cc.

◆ setTolerance()

void rcgccam::ImageList::setTolerance ( uint64_t  tolerance)

Set tolerance for finding corresponding timestamps.

Parameters
toleranceTolerance in nano seconds. Default is 0.

Definition at line 52 of file imagelist.cc.

Member Data Documentation

◆ list_

std::vector<sensor_msgs::ImagePtr> rcgccam::ImageList::list_
private

Definition at line 99 of file imagelist.h.

◆ maxsize_

size_t rcgccam::ImageList::maxsize_
private

Definition at line 97 of file imagelist.h.

◆ tolerance_

uint64_t rcgccam::ImageList::tolerance_
private

Definition at line 98 of file imagelist.h.


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


rc_genicam_camera
Author(s): Heiko Hirschmueller
autogenerated on Wed Mar 2 2022 00:49:18