rgbd
test_serialization.cpp
Go to the documentation of this file.
1 #include <rgbd/serialization.h>
2 #include <rgbd/view.h>
3 #include <rgbd/image.h>
4 
5 #include <fstream>
6 
7 #include <opencv2/highgui/highgui.hpp>
8 
9 #include <sensor_msgs/CameraInfo.h>
10 #include <sensor_msgs/distortion_models.h>
11 
12 int main(int /*argc*/, char **/*argv*/)
13 {
14  std::string test_filename = "/tmp/rgbd_test_image";
15 
16  {
17  sensor_msgs::CameraInfo cam_info;
18  cam_info.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
19  image_geometry::PinholeCameraModel cam_model;
20  cam_model.fromCameraInfo(cam_info);
21 
22  cv::Mat rgb_image(480, 640, CV_8UC3, cv::Scalar(0,0,255));
23  cv::line(rgb_image, cv::Point2i(100, 100), cv::Point2i(200, 300), cv::Scalar(255, 0, 0), 3);
24  cv::Mat depth_image(480, 640, CV_32FC1, 3);
25  cv::line(depth_image, cv::Point2i(100, 100), cv::Point2i(200, 300), cv::Scalar(1), 3);
26 
27  rgbd::Image image(rgb_image, depth_image, cam_model, "no_frame", 0);
28 
29  // write
30  std::ofstream f_out;
31  f_out.open(test_filename.c_str(), std::ifstream::binary);
32 
34 
36  {
37  std::cout << "Could not store image to disk" << std::endl;
38  return 1;
39  }
40  }
41 
42  std::cout << "Image stored to disk." << std::endl;
43 
44  rgbd::Image image;
45 
46  {
47  // read
48  std::ifstream f_in;
49  f_in.open(test_filename.c_str(), std::ifstream::binary);
50 
52 
53  rgbd::deserialize(a_in, image);
54  }
55 
56  std::cout << "Image loaded from disk." << std::endl;
57 // std::cout << " size: " << image.getWidth() << " x " << image.getHeight() << std::endl;
58  std::cout << " frame: " << image.getFrameId() << std::endl;
59  std::cout << " time: " << ros::Time(image.getTimestamp()) << std::endl;
60 
61  if (image.getRGBImage().data)
62  cv::imshow("rgb", image.getRGBImage());
63  else
64  std::cout << "File did not contain RGB data." << std::endl;
65 
66  if (image.getDepthImage().data)
67  cv::imshow("depth", image.getDepthImage() / 8);
68  else
69  std::cout << "File did not contain Depth data" << std::endl;
70  cv::waitKey();
71 
72  return 0;
73 }
fstream
std::string
rgbd::Image::getDepthImage
const cv::Mat & getDepthImage() const
Get the depth image.
Definition: image.h:72
rgbd::Image::getTimestamp
double getTimestamp() const
Get the timestamp.
Definition: image.h:90
rgb_image
cv::Mat rgb_image
Definition: record_to_video.cpp:24
rgbd::deserialize
bool deserialize(tue::serialization::InputArchive &a, Image &image)
Definition: serialization.cpp:174
tue::serialization::OutputArchive
std::cout
rgbd::serialize
bool serialize(const Image &image, tue::serialization::OutputArchive &a, RGBStorageType rgb_type=RGB_STORAGE_JPG, DepthStorageType depth_type=DEPTH_STORAGE_PNG)
Definition: serialization.cpp:23
rgbd::Image
Definition: image.h:43
std::ofstream
std::string::c_str
T c_str(T... args)
main
int main(int, char **)
Definition: test_serialization.cpp:12
std::ofstream::open
T open(T... args)
image.h
rgbd::Image::getRGBImage
const cv::Mat & getRGBImage() const
Get the RGB color image.
Definition: image.h:78
tue::serialization::InputArchive
std::endl
T endl(T... args)
rgbd::RGB_STORAGE_LOSSLESS
@ RGB_STORAGE_LOSSLESS
Definition: image.h:32
rgbd::Image::getFrameId
const std::string & getFrameId() const
Get the frame_id.
Definition: image.h:84
view.h
serialization.h
rgbd::DEPTH_STORAGE_LOSSLESS
@ DEPTH_STORAGE_LOSSLESS
Definition: image.h:39
std::ifstream