Visual Servoing Platform  version 3.6.1 under development (2024-04-20)
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/gui/vpDisplayGDI.h>
7 #include <visp3/gui/vpDisplayX.h>
8 #include <visp3/io/vpImageIo.h>
10 #include <visp3/mbt/vpMbGenericTracker.h>
12 
13 #if defined(VISP_HAVE_PCL)
14 #include <pcl/common/common.h>
15 #include <pcl/io/pcd_io.h>
16 
17 namespace
18 {
19 struct vpRealsenseIntrinsics_t
20 {
21  float ppx;
23  float ppy;
25  float fx;
27  float fy;
29  float coeffs[5];
30 };
31 
32 void rs_deproject_pixel_to_point(float point[3], const vpRealsenseIntrinsics_t &intrin, const float pixel[2], float depth)
33 {
34  float x = (pixel[0] - intrin.ppx) / intrin.fx;
35  float y = (pixel[1] - intrin.ppy) / intrin.fy;
36 
37  float r2 = x * x + y * y;
38  float f = 1 + intrin.coeffs[0] * r2 + intrin.coeffs[1] * r2 * r2 + intrin.coeffs[4] * r2 * r2 * r2;
39  float ux = x * f + 2 * intrin.coeffs[2] * x * y + intrin.coeffs[3] * (r2 + 2 * x * x);
40  float uy = y * f + 2 * intrin.coeffs[3] * x * y + intrin.coeffs[2] * (r2 + 2 * y * y);
41 
42  x = ux;
43  y = uy;
44 
45  point[0] = depth * x;
46  point[1] = depth * y;
47  point[2] = depth;
48 }
49 
51 bool read_data(unsigned int cpt, const std::string &input_directory, vpImage<vpRGBa> &I_color,
52  vpImage<uint16_t> &I_depth_raw, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud)
54 {
55  char buffer[FILENAME_MAX];
56  // Read color
57  std::stringstream ss;
58  ss << input_directory << "/color_image_%04d.jpg";
59  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
60  std::string filename_color = buffer;
61 
62  if (!vpIoTools::checkFilename(filename_color)) {
63  std::cerr << "Cannot read: " << filename_color << std::endl;
64  return false;
65  }
66  vpImageIo::read(I_color, filename_color);
67 
68  // Read raw depth
69  ss.str("");
70  ss << input_directory << "/depth_image_%04d.bin";
71  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
72  std::string filename_depth = buffer;
73 
74  std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
75  if (!file_depth.is_open()) {
76  return false;
77  }
78 
79  unsigned int height = 0, width = 0;
80  vpIoTools::readBinaryValueLE(file_depth, height);
81  vpIoTools::readBinaryValueLE(file_depth, width);
82  I_depth_raw.resize(height, width);
83 
84  uint16_t depth_value = 0;
85  for (unsigned int i = 0; i < height; i++) {
86  for (unsigned int j = 0; j < width; j++) {
87  vpIoTools::readBinaryValueLE(file_depth, depth_value);
88  I_depth_raw[i][j] = depth_value;
89  }
90  }
91 
92  // Transform pointcloud
93  pointcloud->width = width;
94  pointcloud->height = height;
95  pointcloud->resize((size_t)width * height);
96 
97  // Only for Creative SR300
98  const float depth_scale = 0.00100000005f;
99  vpRealsenseIntrinsics_t depth_intrinsic;
100  depth_intrinsic.ppx = 320.503509521484f;
101  depth_intrinsic.ppy = 235.602951049805f;
102  depth_intrinsic.fx = 383.970001220703f;
103  depth_intrinsic.fy = 383.970001220703f;
104  depth_intrinsic.coeffs[0] = 0.0f;
105  depth_intrinsic.coeffs[1] = 0.0f;
106  depth_intrinsic.coeffs[2] = 0.0f;
107  depth_intrinsic.coeffs[3] = 0.0f;
108  depth_intrinsic.coeffs[4] = 0.0f;
109 
110  for (unsigned int i = 0; i < height; i++) {
111  for (unsigned int j = 0; j < width; j++) {
112  float scaled_depth = I_depth_raw[i][j] * depth_scale;
113  float point[3];
114  float pixel[2] = { (float)j, (float)i };
115  rs_deproject_pixel_to_point(point, depth_intrinsic, pixel, scaled_depth);
116  pointcloud->points[(size_t)(i * width + j)].x = point[0];
117  pointcloud->points[(size_t)(i * width + j)].y = point[1];
118  pointcloud->points[(size_t)(i * width + j)].z = point[2];
119  }
120  }
121 
122  return true;
123 }
124 } // namespace
125 
126 int main(int argc, char *argv[])
127 {
128  std::string input_directory = "data"; // location of the data (images, depth_map, point_cloud)
129  std::string config_color = "model/cube/cube.xml", config_depth = "model/cube/cube_depth.xml";
130  std::string model_color = "model/cube/cube.cao", model_depth = "model/cube/cube.cao";
131  std::string init_file = "model/cube/cube.init";
132  unsigned int frame_cpt = 0;
133  bool disable_depth = false;
134 
135  for (int i = 1; i < argc; i++) {
136  if (std::string(argv[i]) == "--input_directory" && i + 1 < argc) {
137  input_directory = std::string(argv[i + 1]);
138  }
139  else if (std::string(argv[i]) == "--config_color" && i + 1 < argc) {
140  config_color = std::string(argv[i + 1]);
141  }
142  else if (std::string(argv[i]) == "--config_depth" && i + 1 < argc) {
143  config_depth = std::string(argv[i + 1]);
144  }
145  else if (std::string(argv[i]) == "--model_color" && i + 1 < argc) {
146  model_color = std::string(argv[i + 1]);
147  }
148  else if (std::string(argv[i]) == "--model_depth" && i + 1 < argc) {
149  model_depth = std::string(argv[i + 1]);
150  }
151  else if (std::string(argv[i]) == "--init_file" && i + 1 < argc) {
152  init_file = std::string(argv[i + 1]);
153  }
154  else if (std::string(argv[i]) == "--disable_depth") {
155  disable_depth = true;
156  }
157  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
158  std::cout << "Usage: \n"
159  << argv[0]
160  << " --input_directory <data directory> --config_color <object.xml> --config_depth <object.xml>"
161  " --model_color <object.cao> --model_depth <object.cao> --init_file <object.init> --disable_depth"
162  << std::endl;
163  std::cout
164  << "\nExample:\n"
165  << argv[0]
166  << " --config_color model/cube/cube.xml --config_depth model/cube/cube.xml"
167  " --model_color model/cube/cube.cao --model_depth model/cube/cube.cao --init_file model/cube/cube.init\n"
168  << std::endl;
169  return EXIT_SUCCESS;
170  }
171  }
172 
173  std::cout << "Tracked features: " << std::endl;
174 #if defined(VISP_HAVE_OPENCV)
175  std::cout << " Use edges : 1" << std::endl;
176 #if defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
177  std::cout << " Use klt : 1" << std::endl;
178 #else
179  std::cout << " Use klt : 0" << std::endl;
180 #endif
181  std::cout << " Use depth : " << !disable_depth << std::endl;
182 #else
183  std::cout << " Use edges : 1" << std::endl;
184  std::cout << " Use klt : 0" << std::endl;
185  std::cout << " Use depth : 0" << std::endl;
186 #endif
187  std::cout << "Config files: " << std::endl;
188  std::cout << " Input directory: "
189  << "\"" << input_directory << "\"" << std::endl;
190  std::cout << " Config color: "
191  << "\"" << config_color << "\"" << std::endl;
192  std::cout << " Config depth: "
193  << "\"" << config_depth << "\"" << std::endl;
194  std::cout << " Model color : "
195  << "\"" << model_color << "\"" << std::endl;
196  std::cout << " Model depth : "
197  << "\"" << model_depth << "\"" << std::endl;
198  std::cout << " Init file : "
199  << "\"" << init_file << "\"" << std::endl;
200 
201  vpImage<vpRGBa> I_color;
203  vpImage<unsigned char> I_gray, I_depth;
205  vpImage<uint16_t> I_depth_raw;
207  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
209  vpCameraParameters cam_color, cam_depth;
210 
211  read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
212  vpImageConvert::convert(I_color, I_gray);
213  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
214 
215 #if defined(VISP_HAVE_X11)
216  vpDisplayX d1, d2;
217 #elif defined(VISP_HAVE_GDI)
218  vpDisplayGDI d1, d2;
219 #endif
220 
221 #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)
222  unsigned int _posx = 100, _posy = 50, _posdx = 10;
223  d1.init(I_gray, _posx, _posy, "Color stream");
224  d2.init(I_depth, _posx + I_gray.getWidth() + _posdx, _posy, "Depth stream");
225 #endif
226 
227  vpDisplay::display(I_gray);
228  vpDisplay::display(I_depth);
229  vpDisplay::flush(I_gray);
230  vpDisplay::flush(I_depth);
231 
233  std::vector<int> trackerTypes;
234 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
236 #else
237  trackerTypes.push_back(vpMbGenericTracker::EDGE_TRACKER);
238 #endif
239  trackerTypes.push_back(vpMbGenericTracker::DEPTH_DENSE_TRACKER);
240  vpMbGenericTracker tracker(trackerTypes);
242 #if defined(VISP_HAVE_PUGIXML)
244  tracker.loadConfigFile(config_color, config_depth);
246 #else
247  {
248  vpCameraParameters cam_color, cam_depth;
249  cam_color.initPersProjWithoutDistortion(614.9, 614.9, 320.2, 241.5);
250  cam_depth.initPersProjWithoutDistortion(384.0, 384.0, 320.5, 235.6);
251  tracker.setCameraParameters(cam_color, cam_depth);
252  }
253 
254  // Edge
255  vpMe me;
256  me.setMaskSize(5);
257  me.setMaskNumber(180);
258  me.setRange(7);
260  me.setThreshold(10);
261  me.setMu1(0.5);
262  me.setMu2(0.5);
263  me.setSampleStep(4);
264  tracker.setMovingEdge(me);
265 
266  // Klt
267 #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
268  vpKltOpencv klt;
269  tracker.setKltMaskBorder(5);
270  klt.setMaxFeatures(300);
271  klt.setWindowSize(5);
272  klt.setQuality(0.01);
273  klt.setMinDistance(5);
274  klt.setHarrisFreeParameter(0.01);
275  klt.setBlockSize(3);
276  klt.setPyramidLevels(3);
277 
278  tracker.setKltOpencv(klt);
279 #endif
280 
281  // Depth
282  tracker.setDepthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION);
283  tracker.setDepthNormalPclPlaneEstimationMethod(2);
284  tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200);
285  tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001);
286  tracker.setDepthNormalSamplingStep(2, 2);
287 
288  tracker.setDepthDenseSamplingStep(4, 4);
289 
290  tracker.setAngleAppear(vpMath::rad(80.0));
291  tracker.setAngleDisappear(vpMath::rad(85.0));
292  tracker.setNearClippingDistance(0.001);
293  tracker.setFarClippingDistance(5.0);
294  tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING);
295 #endif
297  tracker.loadModel(model_color, model_depth);
299 
300  tracker.getCameraParameters(cam_color, cam_depth);
301 
302  std::cout << "Camera parameters for color camera (from XML file): " << cam_color << std::endl;
303  std::cout << "Camera parameters for depth camera (from XML file): " << cam_depth << std::endl;
304 
306  tracker.setDisplayFeatures(true);
308 
310  vpHomogeneousMatrix depth_M_color;
311  {
312  std::ifstream file((std::string(input_directory + "/depth_M_color.txt")).c_str());
313  depth_M_color.load(file);
314  file.close();
315  }
316  std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
317  mapOfCameraTransformations["Camera1"] = vpHomogeneousMatrix();
318  mapOfCameraTransformations["Camera2"] = depth_M_color;
319  tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
321  std::cout << "depth_M_color: \n" << depth_M_color << std::endl;
322 
324  std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
325  mapOfImages["Camera1"] = &I_gray;
326  mapOfImages["Camera2"] = &I_depth;
328 
330  std::map<std::string, std::string> mapOfInitFiles;
331  mapOfInitFiles["Camera1"] = init_file;
332  tracker.initClick(mapOfImages, mapOfInitFiles, true);
334 
335  mapOfImages.clear();
336  pcl::PointCloud<pcl::PointXYZ>::Ptr empty_pointcloud(new pcl::PointCloud<pcl::PointXYZ>);
337  std::vector<double> times_vec;
338 
339  try {
340  bool quit = false;
341  while (!quit) {
342  double t = vpTime::measureTimeMs();
343  quit = !read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
344  vpImageConvert::convert(I_color, I_gray);
345  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
346 
347  vpDisplay::display(I_gray);
348  vpDisplay::display(I_depth);
349 
350  mapOfImages["Camera1"] = &I_gray;
351  std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
352  if (disable_depth)
353  mapOfPointclouds["Camera2"] = empty_pointcloud;
354  else
355  mapOfPointclouds["Camera2"] = pointcloud;
356 
358  tracker.track(mapOfImages, mapOfPointclouds);
360 
362  vpHomogeneousMatrix cMo = tracker.getPose();
364 
365  std::cout << "iter: " << frame_cpt << " cMo:\n" << cMo << std::endl;
366 
368  tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth, vpColor::red, 3);
369  vpDisplay::displayFrame(I_gray, cMo, cam_color, 0.05, vpColor::none, 3);
370  vpDisplay::displayFrame(I_depth, depth_M_color * cMo, cam_depth, 0.05, vpColor::none, 3);
372 
373  t = vpTime::measureTimeMs() - t;
374  times_vec.push_back(t);
375 
376  std::stringstream ss;
377  ss << "Computation time: " << t << " ms";
378  vpDisplay::displayText(I_gray, 20, 20, ss.str(), vpColor::red);
379  {
380  std::stringstream ss;
381  ss << "Nb features: " << tracker.getError().size();
382  vpDisplay::displayText(I_gray, I_gray.getHeight() - 50, 20, ss.str(), vpColor::red);
383  }
384  {
385  std::stringstream ss;
386  ss << "Features: edges " << tracker.getNbFeaturesEdge() << ", klt " << tracker.getNbFeaturesKlt() << ", depth "
387  << tracker.getNbFeaturesDepthDense();
388  vpDisplay::displayText(I_gray, I_gray.getHeight() - 30, 20, ss.str(), vpColor::red);
389  }
390 
391  vpDisplay::flush(I_gray);
392  vpDisplay::flush(I_depth);
393 
395  if (vpDisplay::getClick(I_gray, button, false)) {
396  quit = true;
397  }
398 
399  frame_cpt++;
400  }
401  }
402  catch (const vpException &e) {
403  std::cout << "Catch exception: " << e.getStringMessage() << std::endl;
404  }
405 
406  std::cout << "\nProcessing time, Mean: " << vpMath::getMean(times_vec)
407  << " ms ; Median: " << vpMath::getMedian(times_vec) << " ; Std: " << vpMath::getStdev(times_vec) << " ms"
408  << std::endl;
409 
410  vpDisplay::displayText(I_gray, 60, 20, "Click to quit", vpColor::red);
411  vpDisplay::flush(I_gray);
412  vpDisplay::getClick(I_gray);
413 
414  return EXIT_SUCCESS;
415 }
416 #else
417 int main()
418 {
419  std::cout << "To run this tutorial, ViSP should be build with PCL library."
420  " Install libpcl, configure and build again ViSP..."
421  << std::endl;
422  return EXIT_SUCCESS;
423 }
424 #endif
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
static const vpColor red
Definition: vpColor.h:211
static const vpColor none
Definition: vpColor.h:223
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
void init(vpImage< unsigned char > &I, int win_x=-1, int win_y=-1, const std::string &win_title="") vp_override
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
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), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition: vpException.h:59
const std::string & getStringMessage() const
Definition: vpException.cpp:66
Implementation of an homogeneous matrix and operations on such kind of matrices.
void load(std::ifstream &f)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:143
unsigned int getWidth() const
Definition: vpImage.h:245
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:783
unsigned int getHeight() const
Definition: vpImage.h:184
static bool checkFilename(const std::string &filename)
Definition: vpIoTools.cpp:1213
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
Definition: vpIoTools.cpp:2520
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Definition: vpKltOpencv.h:73
void setBlockSize(int blockSize)
Definition: vpKltOpencv.h:266
void setQuality(double qualityLevel)
Definition: vpKltOpencv.h:355
void setHarrisFreeParameter(double harris_k)
Definition: vpKltOpencv.h:274
void setMaxFeatures(int maxCount)
Definition: vpKltOpencv.h:314
void setMinDistance(double minDistance)
Definition: vpKltOpencv.h:323
void setWindowSize(int winSize)
Definition: vpKltOpencv.h:376
void setPyramidLevels(int pyrMaxLevel)
Definition: vpKltOpencv.h:342
static double rad(double deg)
Definition: vpMath.h:127
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:323
static double getStdev(const std::vector< double > &v, bool useBesselCorrection=false)
Definition: vpMath.cpp:354
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:303
Real-time 6D object pose tracking using its CAD model.
Definition: vpMe.h:124
void setMu1(const double &mu_1)
Definition: vpMe.h:399
void setRange(const unsigned int &range)
Definition: vpMe.h:429
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition: vpMe.h:519
void setMaskNumber(const unsigned int &mask_number)
Definition: vpMe.cpp:488
void setThreshold(const double &threshold)
Definition: vpMe.h:480
void setSampleStep(const double &sample_step)
Definition: vpMe.h:436
void setMaskSize(const unsigned int &mask_size)
Definition: vpMe.cpp:496
void setMu2(const double &mu_2)
Definition: vpMe.h:406
@ NORMALIZED_THRESHOLD
Definition: vpMe.h:135
VISP_EXPORT double measureTimeMs()