rgbd
image.h
Go to the documentation of this file.
1 #ifndef RGBD_IMAGE_H_
2 #define RGBD_IMAGE_H_
3 
4 #include "rgbd/types.h"
5 
6 #include <opencv2/core.hpp>
7 #include <image_geometry/pinhole_camera_model.h>
8 #include <rgbd_msgs/RGBD.h>
9 #include <sensor_msgs/CameraInfo.h>
10 
11 
12 namespace tue
13 {
14 namespace serialization
15 {
16  class InputArchive;
17  class OutputArchive;
18 }
19 }
20 
21 namespace rgbd {
22 
24 {
27 };
28 
30 {
34 };
35 
37 {
41 };
42 
43 class Image {
44 
45  friend class ClientSHM;
46 
47 public:
48 
52  Image();
53 
62  Image(const cv::Mat& rgb_image,
63  const cv::Mat& depth_image,
64  const image_geometry::PinholeCameraModel& cam_model,
65  const std::string& frame_id,
66  double timestamp);
67 
72  inline const cv::Mat& getDepthImage() const { return depth_image_; }
73 
78  inline const cv::Mat& getRGBImage() const { return rgb_image_; }
79 
84  inline const std::string& getFrameId() const { return frame_id_; }
85 
90  inline double getTimestamp() const { return timestamp_; }
91 
96  inline const image_geometry::PinholeCameraModel& getCameraModel() const
97  {
98  return cam_model_;
99  }
100 
105  inline void setDepthImage(const cv::Mat& depth_image) { depth_image_ = depth_image; }
106 
111  inline void setRGBImage(const cv::Mat& rgb_image) { rgb_image_ = rgb_image; }
112 
117  inline void setFrameId(const std::string& frame_id) { frame_id_ = frame_id; }
118 
123  inline void setTimestamp(double timestamp) { timestamp_ = timestamp; }
124 
130  void setCameraInfo(sensor_msgs::CameraInfo cam_info);
131 
137  void setCameraModel(const image_geometry::PinholeCameraModel& cam_model);
138 
144  Image clone() const;
145 
151  bool operator==(const rgbd::Image& other) const;
152 
158  inline bool operator!=(const rgbd::Image& other) const { return !(*this == other); }
159 
160  friend std::ostream& operator<< (std::ostream& out, const rgbd::Image& image);
161 
162  friend bool serialize(const Image& image, tue::serialization::OutputArchive& a,
163  RGBStorageType rgb_type,
164  DepthStorageType depth_type);
165 
166  friend bool deserialize(tue::serialization::InputArchive& a, Image& image);
167 
168  friend bool convert(const rgbd_msgs::RGBDConstPtr& msg, rgbd::Image*& image);
169 
170 protected:
171 
172  cv::Mat rgb_image_; // BGR format
173  cv::Mat depth_image_;
174 
179  image_geometry::PinholeCameraModel cam_model_;
180 
182  double timestamp_;
183 
184 };
185 
186 }
187 
188 #endif // RGBD_IMAGE_H_
std::string
rgbd::Image::getDepthImage
const cv::Mat & getDepthImage() const
Get the depth image.
Definition: image.h:72
rgbd::Image::cam_model_
image_geometry::PinholeCameraModel cam_model_
Camera model Header in camera info should always be empty to prevent inconsistent behaviour of equali...
Definition: image.h:179
rgbd::Image::getTimestamp
double getTimestamp() const
Get the timestamp.
Definition: image.h:90
types.h
rgb_image
cv::Mat rgb_image
Definition: record_to_video.cpp:24
rgbd::Image::operator==
bool operator==(const rgbd::Image &other) const
Equality operator.
Definition: image.cpp:71
rgbd::Image::setDepthImage
void setDepthImage(const cv::Mat &depth_image)
Set the depth image.
Definition: image.h:105
tue::serialization::OutputArchive
rgbd::CAMERA_MODEL_PINHOLE
@ CAMERA_MODEL_PINHOLE
Definition: image.h:26
rgbd::Image::operator<<
friend std::ostream & operator<<(std::ostream &out, const rgbd::Image &image)
Definition: image.cpp:106
rgbd::Image::setFrameId
void setFrameId(const std::string &frame_id)
Set the frame_id.
Definition: image.h:117
rgbd::Image::setRGBImage
void setRGBImage(const cv::Mat &rgb_image)
Set the BGR color image.
Definition: image.h:111
rgbd::Image::operator!=
bool operator!=(const rgbd::Image &other) const
Non-equality operator.
Definition: image.h:158
rgbd::CameraModelType
CameraModelType
Definition: image.h:23
rgbd::DepthStorageType
DepthStorageType
Definition: image.h:36
rgbd::Image::frame_id_
std::string frame_id_
Definition: image.h:181
rgbd::Image
Definition: image.h:43
rgbd::Image::setTimestamp
void setTimestamp(double timestamp)
Set the timestamp.
Definition: image.h:123
rgbd::Image::convert
friend bool convert(const rgbd_msgs::RGBDConstPtr &msg, rgbd::Image *&image)
Convert rgbd message to an Image.
Definition: conversions.cpp:88
rgbd::Image::deserialize
friend bool deserialize(tue::serialization::InputArchive &a, Image &image)
Definition: serialization.cpp:174
std::ostream
rgbd::RGB_STORAGE_JPG
@ RGB_STORAGE_JPG
Definition: image.h:33
rgbd::Image::setCameraModel
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 e...
Definition: image.cpp:45
rgbd
Definition: client.h:24
rgbd::RGBStorageType
RGBStorageType
Definition: image.h:29
rgbd::DEPTH_STORAGE_NONE
@ DEPTH_STORAGE_NONE
Definition: image.h:38
rgbd::Image::serialize
friend bool serialize(const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type, DepthStorageType depth_type)
Definition: serialization.cpp:23
rgbd::Image::getRGBImage
const cv::Mat & getRGBImage() const
Get the RGB color image.
Definition: image.h:78
rgbd::Image::Image
Image()
Empty constructor.
Definition: image.cpp:13
rgbd::DEPTH_STORAGE_PNG
@ DEPTH_STORAGE_PNG
Definition: image.h:40
rgbd::Image::clone
Image clone() const
Create a clone of this image. The depth and RGB images will be cloned, so the new image will not shar...
Definition: image.cpp:56
tue::serialization::InputArchive
rgbd::Image::depth_image_
cv::Mat depth_image_
Definition: image.h:173
rgbd::RGB_STORAGE_LOSSLESS
@ RGB_STORAGE_LOSSLESS
Definition: image.h:32
rgbd::Image::timestamp_
double timestamp_
Definition: image.h:182
rgbd::Image::getCameraModel
const image_geometry::PinholeCameraModel & getCameraModel() const
Get the camera model.
Definition: image.h:96
rgbd::Image::getFrameId
const std::string & getFrameId() const
Get the frame_id.
Definition: image.h:84
rgbd::Image::setCameraInfo
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 b...
Definition: image.cpp:34
rgbd::DEPTH_STORAGE_LOSSLESS
@ DEPTH_STORAGE_LOSSLESS
Definition: image.h:39
rgbd::CAMERA_MODEL_NONE
@ CAMERA_MODEL_NONE
Definition: image.h:25
rgbd::RGB_STORAGE_NONE
@ RGB_STORAGE_NONE
Definition: image.h:31
tue
rgbd::ClientSHM
Client which uses shared memory, requires a server on the same machine.
Definition: client_shm.h:16
rgbd::Image::rgb_image_
cv::Mat rgb_image_
Definition: image.h:172