#include <image.h>
Definition at line 43 of file image.h.
◆ Image() [1/2]
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_image | Resulting RGB color image. |
depth_image | Resulting depth image. |
cam_model | Camera model used to take the image. |
frame_id | Frame_id in which the image is taken. |
timestamp | timestamp of the image. |
Definition at line 19 of file image.cpp.
◆ 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()
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
-
other | Other 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
-
other | Other 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_info | The 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_model | The 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_image | The 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_id | The 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_image | The 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
-
timestamp | The timestamp to set. |
Definition at line 123 of file image.h.
◆ ClientSHM
◆ convert
bool convert |
( |
const rgbd_msgs::RGBDConstPtr & |
msg, |
|
|
rgbd::Image *& |
image |
|
) |
| |
|
friend |
Convert rgbd message to an Image.
- Parameters
-
msg | pointer to const rgbd message |
image | raw 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
◆ operator<<
◆ serialize
◆ 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 |
◆ frame_id_
◆ rgb_image_
cv::Mat rgbd::Image::rgb_image_ |
|
protected |
◆ timestamp_
double rgbd::Image::timestamp_ |
|
protected |
The documentation for this class was generated from the following files: