rgbd
Public Member Functions | Protected Attributes | Friends | List of all members
rgbd::Image Class Reference

#include <image.h>

Public Member Functions

Image clone () const
 Create a clone of this image. The depth and RGB images will be cloned, so the new image will not share data. More...
 
const image_geometry::PinholeCameraModel & getCameraModel () const
 Get the camera model. More...
 
const cv::Mat & getDepthImage () const
 Get the depth image. More...
 
const std::stringgetFrameId () const
 Get the frame_id. More...
 
const cv::Mat & getRGBImage () const
 Get the RGB color image. More...
 
double getTimestamp () const
 Get the timestamp. More...
 
 Image ()
 Empty constructor. More...
 
 Image (const cv::Mat &rgb_image, const cv::Mat &depth_image, const image_geometry::PinholeCameraModel &cam_model, const std::string &frame_id, double timestamp)
 Full constructor. More...
 
bool operator!= (const rgbd::Image &other) const
 Non-equality operator. More...
 
bool operator== (const rgbd::Image &other) const
 Equality operator. More...
 
void setCameraInfo (sensor_msgs::CameraInfo cam_info)
 Set the camera model by using a camera info message. The frame_id and timestamp of the message will be emptied. More...
 
void setCameraModel (const image_geometry::PinholeCameraModel &cam_model)
 Set the camera model. The frame_id and timestamp in the camera info inside the camera model will be emptied. More...
 
void setDepthImage (const cv::Mat &depth_image)
 Set the depth image. More...
 
void setFrameId (const std::string &frame_id)
 Set the frame_id. More...
 
void setRGBImage (const cv::Mat &rgb_image)
 Set the BGR color image. More...
 
void setTimestamp (double timestamp)
 Set the timestamp. More...
 

Protected Attributes

image_geometry::PinholeCameraModel cam_model_
 Camera model Header in camera info should always be empty to prevent inconsistent behaviour of equality operators. More...
 
cv::Mat depth_image_
 
std::string frame_id_
 
cv::Mat rgb_image_
 
double timestamp_
 

Friends

class ClientSHM
 
bool convert (const rgbd_msgs::RGBDConstPtr &msg, rgbd::Image *&image)
 Convert rgbd message to an Image. More...
 
bool deserialize (tue::serialization::InputArchive &a, Image &image)
 
std::ostreamoperator<< (std::ostream &out, const rgbd::Image &image)
 
bool serialize (const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type, DepthStorageType depth_type)
 

Detailed Description

Definition at line 43 of file image.h.

Constructor & Destructor Documentation

◆ Image() [1/2]

rgbd::Image::Image ( )

Empty constructor.

Definition at line 13 of file image.cpp.

◆ Image() [2/2]

rgbd::Image::Image ( const cv::Mat &  rgb_image,
const cv::Mat &  depth_image,
const image_geometry::PinholeCameraModel &  cam_model,
const std::string frame_id,
double  timestamp 
)

Full constructor.

Parameters
rgb_imageResulting RGB color image.
depth_imageResulting depth image.
cam_modelCamera model used to take the image.
frame_idFrame_id in which the image is taken.
timestamptimestamp of the image.

Definition at line 19 of file image.cpp.

Member Function Documentation

◆ clone()

Image rgbd::Image::clone ( ) const

Create a clone of this image. The depth and RGB images will be cloned, so the new image will not share data.

Returns
New image.

Definition at line 56 of file image.cpp.

◆ getCameraModel()

const image_geometry::PinholeCameraModel& rgbd::Image::getCameraModel ( ) const
inline

Get the camera model.

Returns
Const reference to the camera model.

Definition at line 96 of file image.h.

◆ getDepthImage()

const cv::Mat& rgbd::Image::getDepthImage ( ) const
inline

Get the depth image.

Returns
Const reference to the depth image.

Definition at line 72 of file image.h.

◆ getFrameId()

const std::string& rgbd::Image::getFrameId ( ) const
inline

Get the frame_id.

Returns
Const reference to the frame_id.

Definition at line 84 of file image.h.

◆ getRGBImage()

const cv::Mat& rgbd::Image::getRGBImage ( ) const
inline

Get the RGB color image.

Returns
Const reference to the RGB color image.

Definition at line 78 of file image.h.

◆ getTimestamp()

double rgbd::Image::getTimestamp ( ) const
inline

Get the timestamp.

Returns
Copy of the timestamp.

Definition at line 90 of file image.h.

◆ operator!=()

bool rgbd::Image::operator!= ( const rgbd::Image other) const
inline

Non-equality operator.

Parameters
otherOther image to compare with.
Returns
non-equality

Definition at line 158 of file image.h.

◆ operator==()

bool rgbd::Image::operator== ( const rgbd::Image other) const

Equality operator.

Parameters
otherOther image to compare with.
Returns
equality

Definition at line 71 of file image.cpp.

◆ setCameraInfo()

void rgbd::Image::setCameraInfo ( sensor_msgs::CameraInfo  cam_info)

Set the camera model by using a camera info message. The frame_id and timestamp of the message will be emptied.

Parameters
cam_infoThe camera info message to construct the camera model.

Definition at line 34 of file image.cpp.

◆ setCameraModel()

void rgbd::Image::setCameraModel ( const image_geometry::PinholeCameraModel &  cam_model)

Set the camera model. The frame_id and timestamp in the camera info inside the camera model will be emptied.

Parameters
cam_modelThe camera model to set.

Definition at line 45 of file image.cpp.

◆ setDepthImage()

void rgbd::Image::setDepthImage ( const cv::Mat &  depth_image)
inline

Set the depth image.

Parameters
depth_imageThe depth image to set.

Definition at line 105 of file image.h.

◆ setFrameId()

void rgbd::Image::setFrameId ( const std::string frame_id)
inline

Set the frame_id.

Parameters
frame_idThe frame_id to set.

Definition at line 117 of file image.h.

◆ setRGBImage()

void rgbd::Image::setRGBImage ( const cv::Mat &  rgb_image)
inline

Set the BGR color image.

Parameters
depth_imageThe BGR color image to set.

Definition at line 111 of file image.h.

◆ setTimestamp()

void rgbd::Image::setTimestamp ( double  timestamp)
inline

Set the timestamp.

Parameters
timestampThe timestamp to set.

Definition at line 123 of file image.h.

Friends And Related Function Documentation

◆ ClientSHM

friend class ClientSHM
friend

Definition at line 45 of file image.h.

◆ convert

bool convert ( const rgbd_msgs::RGBDConstPtr &  msg,
rgbd::Image *&  image 
)
friend

Convert rgbd message to an Image.

Parameters
msgpointer to const rgbd message
imageraw pointer to an Image. In case it is a nullptr, a new instance will be created.
Returns
success

Definition at line 88 of file conversions.cpp.

◆ deserialize

bool deserialize ( tue::serialization::InputArchive a,
Image image 
)
friend

Definition at line 174 of file serialization.cpp.

◆ operator<<

std::ostream& operator<< ( std::ostream out,
const rgbd::Image image 
)
friend

Definition at line 106 of file image.cpp.

◆ serialize

bool serialize ( const Image image,
tue::serialization::OutputArchive a,
RGBStorageType  rgb_type = RGB_STORAGE_JPG,
DepthStorageType  depth_type = DEPTH_STORAGE_PNG 
)
friend

Definition at line 23 of file serialization.cpp.

Member Data Documentation

◆ cam_model_

image_geometry::PinholeCameraModel rgbd::Image::cam_model_
protected

Camera model Header in camera info should always be empty to prevent inconsistent behaviour of equality operators.

Definition at line 179 of file image.h.

◆ depth_image_

cv::Mat rgbd::Image::depth_image_
protected

Definition at line 173 of file image.h.

◆ frame_id_

std::string rgbd::Image::frame_id_
protected

Definition at line 181 of file image.h.

◆ rgb_image_

cv::Mat rgbd::Image::rgb_image_
protected

Definition at line 172 of file image.h.

◆ timestamp_

double rgbd::Image::timestamp_
protected

Definition at line 182 of file image.h.


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