Go to the documentation of this file.
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>
14 namespace serialization
63 const cv::Mat& depth_image,
64 const image_geometry::PinholeCameraModel& cam_model,
137 void setCameraModel(
const image_geometry::PinholeCameraModel& cam_model);
188 #endif // RGBD_IMAGE_H_
const cv::Mat & getDepthImage() const
Get the depth image.
image_geometry::PinholeCameraModel cam_model_
Camera model Header in camera info should always be empty to prevent inconsistent behaviour of equali...
double getTimestamp() const
Get the timestamp.
bool operator==(const rgbd::Image &other) const
Equality operator.
void setDepthImage(const cv::Mat &depth_image)
Set the depth image.
friend std::ostream & operator<<(std::ostream &out, const rgbd::Image &image)
void setFrameId(const std::string &frame_id)
Set the frame_id.
void setRGBImage(const cv::Mat &rgb_image)
Set the BGR color image.
bool operator!=(const rgbd::Image &other) const
Non-equality operator.
void setTimestamp(double timestamp)
Set the timestamp.
friend bool convert(const rgbd_msgs::RGBDConstPtr &msg, rgbd::Image *&image)
Convert rgbd message to an Image.
friend bool deserialize(tue::serialization::InputArchive &a, Image &image)
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...
friend bool serialize(const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type, DepthStorageType depth_type)
const cv::Mat & getRGBImage() const
Get the RGB color image.
Image()
Empty constructor.
Image clone() const
Create a clone of this image. The depth and RGB images will be cloned, so the new image will not shar...
const image_geometry::PinholeCameraModel & getCameraModel() const
Get the camera model.
const std::string & getFrameId() const
Get the frame_id.
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...
Client which uses shared memory, requires a server on the same machine.