Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
tutorial-mb-generic-tracker-rgbd.cpp
1 #include <iostream>
3 
4 #include <visp3/core/vpDisplay.h>
5 #include <visp3/core/vpIoTools.h>
6 #include <visp3/io/vpImageIo.h>
7 #include <visp3/core/vpXmlParserCamera.h>
8 #include <visp3/gui/vpDisplayGDI.h>
9 #include <visp3/gui/vpDisplayX.h>
11 #include <visp3/mbt/vpMbGenericTracker.h>
13 
14 #if defined (VISP_HAVE_PCL)
15 #include <pcl/common/common.h>
16 #include <pcl/io/pcd_io.h>
17 
18 struct rs_intrinsics {
19  float ppx;
21  float ppy;
23  float fx;
25  float fy;
27  float coeffs[5];
28 };
29 
30 void rs_deproject_pixel_to_point(float point[3], const rs_intrinsics &intrin, const float pixel[2], float depth) {
31  float x = (pixel[0] - intrin.ppx) / intrin.fx;
32  float y = (pixel[1] - intrin.ppy) / intrin.fy;
33 
34  float r2 = x * x + y * y;
35  float f = 1 + intrin.coeffs[0] * r2 + intrin.coeffs[1] * r2 * r2 + intrin.coeffs[4] * r2 * r2 * r2;
36  float ux = x * f + 2 * intrin.coeffs[2] * x * y + intrin.coeffs[3] * (r2 + 2 * x * x);
37  float uy = y * f + 2 * intrin.coeffs[3] * x * y + intrin.coeffs[2] * (r2 + 2 * y * y);
38 
39  x = ux;
40  y = uy;
41 
42  point[0] = depth * x;
43  point[1] = depth * y;
44  point[2] = depth;
45 }
46 
48 bool read_data(unsigned int cpt, const std::string &input_directory, vpImage<vpRGBa> &I_color,
49  vpImage<uint16_t> &I_depth_raw, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud)
51 {
52  char buffer[FILENAME_MAX];
53  // Read color
54  std::stringstream ss;
55  ss << input_directory << "/color_image_%04d.jpg";
56  sprintf(buffer, ss.str().c_str(), cpt);
57  std::string filename_color = buffer;
58 
59  if (!vpIoTools::checkFilename(filename_color)) {
60  std::cerr << "Cannot read: " << filename_color << std::endl;
61  return false;
62  }
63  vpImageIo::read(I_color, filename_color);
64 
65  // Read raw depth
66  ss.str("");
67  ss << input_directory << "/depth_image_%04d.bin";
68  sprintf(buffer, ss.str().c_str(), cpt);
69  std::string filename_depth = buffer;
70 
71  std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
72  if (!file_depth.is_open()) {
73  return false;
74  }
75 
76  unsigned int height = 0, width = 0;
77  vpIoTools::readBinaryValueLE(file_depth, height);
78  vpIoTools::readBinaryValueLE(file_depth, width);
79 
80  I_depth_raw.resize(height, width);
81 
82  uint16_t depth_value = 0;
83  for (unsigned int i = 0; i < height; i++) {
84  for (unsigned int j = 0; j < width; j++) {
85  vpIoTools::readBinaryValueLE(file_depth, depth_value);
86  I_depth_raw[i][j] = depth_value;
87  }
88  }
89 
90  // Transform pointcloud
91  pointcloud->width = width;
92  pointcloud->height = height;
93  pointcloud->reserve((size_t)width * height);
94 
95  // Only for Creative SR300
96  const float depth_scale = 0.00100000005f;
97  rs_intrinsics depth_intrinsic;
98  depth_intrinsic.ppx = 320.503509521484f;
99  depth_intrinsic.ppy = 235.602951049805f;
100  depth_intrinsic.fx = 383.970001220703f;
101  depth_intrinsic.fy = 383.970001220703f;
102  depth_intrinsic.coeffs[0] = 0.0f;
103  depth_intrinsic.coeffs[1] = 0.0f;
104  depth_intrinsic.coeffs[2] = 0.0f;
105  depth_intrinsic.coeffs[3] = 0.0f;
106  depth_intrinsic.coeffs[4] = 0.0f;
107 
108  for (unsigned int i = 0; i < height; i++) {
109  for (unsigned int j = 0; j < width; j++) {
110  float scaled_depth = I_depth_raw[i][j] * depth_scale;
111  float point[3];
112  float pixel[2] = {(float)j, (float)i};
113  rs_deproject_pixel_to_point(point, depth_intrinsic, pixel, scaled_depth);
114  pointcloud->push_back(pcl::PointXYZ(point[0], point[1], point[2]));
115  }
116  }
117 
118  return true;
119 }
120 
121 int main(int argc, char *argv[])
122 {
123  std::string input_directory = "."; // location of the data (images, depth_map, point_cloud)
124  std::string config_color = "cube.xml", config_depth = "cube_depth.xml";
125  std::string model_color = "cube.cao", model_depth = "cube.cao";
126  std::string init_file = "cube.init";
127  int frame_cpt = 0;
128  bool disable_depth = false;
129 
130  for (int i = 1; i < argc; i++) {
131  if (std::string(argv[i]) == "--input_directory" && i+1 < argc) {
132  input_directory = std::string(argv[i+1]);
133  } else if (std::string(argv[i]) == "--config_color" && i+1 < argc) {
134  config_color = std::string(argv[i+1]);
135  } else if (std::string(argv[i]) == "--config_depth" && i+1 < argc) {
136  config_depth = std::string(argv[i+1]);
137  } else if (std::string(argv[i]) == "--model_color" && i+1 < argc) {
138  model_color = std::string(argv[i+1]);
139  } else if (std::string(argv[i]) == "--model_depth" && i+1 < argc) {
140  model_depth = std::string(argv[i+1]);
141  } else if (std::string(argv[i]) == "--init_file" && i+1 < argc) {
142  init_file = std::string(argv[i+1]);
143  } else if (std::string(argv[i]) == "--disable_depth") {
144  disable_depth = true;
145  } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
146  std::cout << "Usage: \n" << argv[0] << " --input_directory <data directory> --config_color <object.xml> --config_depth <object.xml>"
147  " --model_color <object.cao> --model_depth <object.cao> --init_file <object.init> --disable_depth" << std::endl;
148  std::cout << "\nExample:\n" << argv[0] << " --config_color ../model/cube/cube.xml --config_depth ../model/cube/cube.xml"
149  " --model_color ../model/cube/cube.cao --model_depth ../model/cube/cube.cao --init_file ../model/cube/cube.init\n" << std::endl;
150  return 0;
151  }
152  }
153 
154  vpImage<vpRGBa> I_color;
156  vpImage<unsigned char> I_gray, I_depth;
158  vpImage<uint16_t> I_depth_raw;
160  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
162  vpCameraParameters cam_color, cam_depth;
163  unsigned int _posx = 100, _posy = 50, _posdx = 10;
164 
165  read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
166  vpImageConvert::convert(I_color, I_gray);
167  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
168 
169 #if defined(VISP_HAVE_X11)
170  vpDisplayX d1, d2;
171 #elif defined(VISP_HAVE_GDI)
172  vpDisplayGDI d1, d2;
173 #endif
174  d1.init(I_gray, _posx, _posy, "Color stream");
175  d2.init(I_depth, _posx + I_gray.getWidth()+_posdx, _posy, "Depth stream");
176  vpDisplay::display(I_gray);
177  vpDisplay::display(I_depth);
178  vpDisplay::flush(I_gray);
179  vpDisplay::flush(I_depth);
180 
182 #ifdef VISP_HAVE_OPENCV
184 #else
185  std::vector<int> trackerTypes = {vpMbGenericTracker::EDGE_TRACKER};
186 #endif
187  vpMbGenericTracker tracker(trackerTypes);
190  tracker.loadConfigFile(config_color, config_depth);
193  tracker.loadModel(model_color, model_depth);
195 
196  tracker.getCameraParameters(cam_color, cam_depth);
197 
198  std::cout << "Camera parameters for color camera (from XML file): " << cam_color << std::endl;
199  std::cout << "Camera parameters for depth camera (from XML file): " << cam_depth << std::endl;
200 
202  tracker.setDisplayFeatures(true);
204 
206  vpHomogeneousMatrix depth_M_color;
207  {
208  std::ifstream file( std::string(input_directory + "/depth_M_color.txt") );
209  depth_M_color.load(file);
210  file.close();
211  }
212  std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
213  mapOfCameraTransformations["Camera1"] = vpHomogeneousMatrix();
214  mapOfCameraTransformations["Camera2"] = depth_M_color;
215  tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
217  std::cout << "depth_M_color: \n" << depth_M_color << std::endl;
218 
220  std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
221  mapOfImages["Camera1"] = &I_gray;
222  mapOfImages["Camera2"] = &I_depth;
224 
226  std::map<std::string, std::string> mapOfInitFiles;
227  mapOfInitFiles["Camera1"] = init_file;
228  tracker.initClick(mapOfImages, mapOfInitFiles, true);
230 
231  mapOfImages.clear();
232  pcl::PointCloud<pcl::PointXYZ>::Ptr empty_pointcloud(new pcl::PointCloud<pcl::PointXYZ>);
233  std::vector<double> times_vec;
234 
235  try {
236  bool quit = false;
237  while (! quit) {
238  double t = vpTime::measureTimeMs();
239  read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
240  vpImageConvert::convert(I_color, I_gray);
241  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
242 
243  vpDisplay::display(I_gray);
244  vpDisplay::display(I_depth);
245 
246  mapOfImages["Camera1"] = &I_gray;
247  std::map<std::string, pcl::PointCloud< pcl::PointXYZ >::ConstPtr> mapOfPointclouds;
248  if (disable_depth)
249  mapOfPointclouds["Camera2"] = empty_pointcloud;
250  else
251  mapOfPointclouds["Camera2"] = pointcloud;
252 
254  tracker.track(mapOfImages, mapOfPointclouds);
256 
258  vpHomogeneousMatrix cMo = tracker.getPose();
260 
261  std::cout << "iter: " << frame_cpt << " cMo:\n" << cMo << std::endl;
262 
264  tracker.display(I_gray, I_depth, cMo, depth_M_color*cMo, cam_color, cam_depth, vpColor::red, 3);
265  vpDisplay::displayFrame(I_gray, cMo, cam_color, 0.05, vpColor::none, 3);
266  vpDisplay::displayFrame(I_depth, depth_M_color*cMo, cam_depth, 0.05, vpColor::none, 3);
268 
269  t = vpTime::measureTimeMs() - t;
270  times_vec.push_back(t);
271 
272  std::stringstream ss;
273  ss << "Computation time: " << t << " ms";
274  vpDisplay::displayText(I_gray, 20, 20, ss.str(), vpColor::red);
275 
276  vpDisplay::flush(I_gray);
277  vpDisplay::flush(I_depth);
278 
280  if (vpDisplay::getClick(I_gray, button, false)) {
281  quit = true;
282  }
283 
284  frame_cpt ++;
285  }
286  } catch (const vpException &e) {
287  std::cout << "Catch exception: " << e.getStringMessage() << std::endl;
288  }
289 
290  std::cout << "\nProcessing time, Mean: " << vpMath::getMean(times_vec) << " ms ; Median: " << vpMath::getMedian(times_vec)
291  << " ; Std: " << vpMath::getStdev(times_vec) << " ms" << std::endl;
292 
293  return EXIT_SUCCESS;
294 }
295 #else
296 int main()
297 {
298  std::cout << "To run this tutorial, ViSP should be build with PCL library."
299  " Install libpcl, configure and build again ViSP..." << std::endl;
300  return EXIT_SUCCESS;
301 }
302 #endif
virtual void setDisplayFeatures(const bool displayF)
virtual void loadConfigFile(const std::string &configFile)
virtual void track(const vpImage< unsigned char > &I)
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static double getStdev(const std::vector< double > &v, const bool useBesselCorrection=false)
Definition: vpMath.cpp:252
unsigned int getWidth() const
Definition: vpImage.h:239
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
Definition: vpIoTools.cpp:1864
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:222
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:129
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
static const vpColor none
Definition: vpColor.h:192
error that can be emited by ViSP classes.
Definition: vpException.h:71
virtual void getCameraParameters(vpCameraParameters &cam1, vpCameraParameters &cam2) const
Real-time 6D object pose tracking using its CAD model.
static void flush(const vpImage< unsigned char > &I)
void load(std::ifstream &f)
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:88
static const vpColor red
Definition: vpColor.h:180
static bool checkFilename(const char *filename)
Definition: vpIoTools.cpp:675
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:202
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, const unsigned int thickness=1, const bool displayFullModel=false)
virtual void initClick(const vpImage< unsigned char > &I1, const vpImage< unsigned char > &I2, const std::string &initFile1, const std::string &initFile2, const bool displayHelp=false, const vpHomogeneousMatrix &T1=vpHomogeneousMatrix(), const vpHomogeneousMatrix &T2=vpHomogeneousMatrix())
static void display(const vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void resize(const unsigned int h, const unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:866
virtual void loadModel(const std::string &modelFile, const bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
static void read(vpImage< unsigned char > &I, const std::string &filename)
Definition: vpImageIo.cpp:207
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0))
virtual void getPose(vpHomogeneousMatrix &c1Mo, vpHomogeneousMatrix &c2Mo) const
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
const std::string & getStringMessage(void) const
Send a reference (constant) related the error message (can be empty).
Definition: vpException.cpp:92
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
virtual void setCameraTransformationMatrix(const std::string &cameraName, const vpHomogeneousMatrix &cameraTransformationMatrix)