Visual Servoing Platform  version 3.6.1 under development (2024-04-25)
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) && defined(VISP_HAVE_PCL_COMMON)
14 #include <pcl/common/common.h>
15 #include <pcl/point_cloud.h>
16 #include <pcl/point_types.h>
17 
18 namespace
19 {
20 struct vpRealsenseIntrinsics_t
21 {
22  float ppx;
24  float ppy;
26  float fx;
28  float fy;
30  float coeffs[5];
31 };
32 
33 void rs_deproject_pixel_to_point(float point[3], const vpRealsenseIntrinsics_t &intrin, const float pixel[2], float depth)
34 {
35  float x = (pixel[0] - intrin.ppx) / intrin.fx;
36  float y = (pixel[1] - intrin.ppy) / intrin.fy;
37 
38  float r2 = x * x + y * y;
39  float f = 1 + intrin.coeffs[0] * r2 + intrin.coeffs[1] * r2 * r2 + intrin.coeffs[4] * r2 * r2 * r2;
40  float ux = x * f + 2 * intrin.coeffs[2] * x * y + intrin.coeffs[3] * (r2 + 2 * x * x);
41  float uy = y * f + 2 * intrin.coeffs[3] * x * y + intrin.coeffs[2] * (r2 + 2 * y * y);
42 
43  x = ux;
44  y = uy;
45 
46  point[0] = depth * x;
47  point[1] = depth * y;
48  point[2] = depth;
49 }
50 
52 bool read_data(unsigned int cpt, const std::string &input_directory, vpImage<vpRGBa> &I_color,
53  vpImage<uint16_t> &I_depth_raw, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud)
55 {
56  char buffer[FILENAME_MAX];
57  // Read color
58  std::stringstream ss;
59  ss << input_directory << "/color_image_%04d.jpg";
60  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
61  std::string filename_color = buffer;
62 
63  if (!vpIoTools::checkFilename(filename_color)) {
64  std::cerr << "Cannot read: " << filename_color << std::endl;
65  return false;
66  }
67  vpImageIo::read(I_color, filename_color);
68 
69  // Read raw depth
70  ss.str("");
71  ss << input_directory << "/depth_image_%04d.bin";
72  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
73  std::string filename_depth = buffer;
74 
75  std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
76  if (!file_depth.is_open()) {
77  return false;
78  }
79 
80  unsigned int height = 0, width = 0;
81  vpIoTools::readBinaryValueLE(file_depth, height);
82  vpIoTools::readBinaryValueLE(file_depth, width);
83  I_depth_raw.resize(height, width);
84 
85  uint16_t depth_value = 0;
86  for (unsigned int i = 0; i < height; i++) {
87  for (unsigned int j = 0; j < width; j++) {
88  vpIoTools::readBinaryValueLE(file_depth, depth_value);
89  I_depth_raw[i][j] = depth_value;
90  }
91  }
92 
93  // Transform pointcloud
94  pointcloud->width = width;
95  pointcloud->height = height;
96  pointcloud->resize((size_t)width * height);
97 
98  // Only for Creative SR300
99  const float depth_scale = 0.00100000005f;
100  vpRealsenseIntrinsics_t depth_intrinsic;
101  depth_intrinsic.ppx = 320.503509521484f;
102  depth_intrinsic.ppy = 235.602951049805f;
103  depth_intrinsic.fx = 383.970001220703f;
104  depth_intrinsic.fy = 383.970001220703f;
105  depth_intrinsic.coeffs[0] = 0.0f;
106  depth_intrinsic.coeffs[1] = 0.0f;
107  depth_intrinsic.coeffs[2] = 0.0f;
108  depth_intrinsic.coeffs[3] = 0.0f;
109  depth_intrinsic.coeffs[4] = 0.0f;
110 
111  for (unsigned int i = 0; i < height; i++) {
112  for (unsigned int j = 0; j < width; j++) {
113  float scaled_depth = I_depth_raw[i][j] * depth_scale;
114  float point[3];
115  float pixel[2] = { (float)j, (float)i };
116  rs_deproject_pixel_to_point(point, depth_intrinsic, pixel, scaled_depth);
117  pointcloud->points[(size_t)(i * width + j)].x = point[0];
118  pointcloud->points[(size_t)(i * width + j)].y = point[1];
119  pointcloud->points[(size_t)(i * width + j)].z = point[2];
120  }
121  }
122 
123  return true;
124 }
125 } // namespace
126 
127 int main(int argc, char *argv[])
128 {
129  std::string input_directory = "data"; // location of the data (images, depth_map, point_cloud)
130  std::string config_color = "model/cube/cube.xml", config_depth = "model/cube/cube_depth.xml";
131  std::string model_color = "model/cube/cube.cao", model_depth = "model/cube/cube.cao";
132  std::string init_file = "model/cube/cube.init";
133  unsigned int frame_cpt = 0;
134  bool disable_depth = false;
135 
136  for (int i = 1; i < argc; i++) {
137  if (std::string(argv[i]) == "--input_directory" && i + 1 < argc) {
138  input_directory = std::string(argv[i + 1]);
139  }
140  else if (std::string(argv[i]) == "--config_color" && i + 1 < argc) {
141  config_color = std::string(argv[i + 1]);
142  }
143  else if (std::string(argv[i]) == "--config_depth" && i + 1 < argc) {
144  config_depth = std::string(argv[i + 1]);
145  }
146  else if (std::string(argv[i]) == "--model_color" && i + 1 < argc) {
147  model_color = std::string(argv[i + 1]);
148  }
149  else if (std::string(argv[i]) == "--model_depth" && i + 1 < argc) {
150  model_depth = std::string(argv[i + 1]);
151  }
152  else if (std::string(argv[i]) == "--init_file" && i + 1 < argc) {
153  init_file = std::string(argv[i + 1]);
154  }
155  else if (std::string(argv[i]) == "--disable_depth") {
156  disable_depth = true;
157  }
158  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
159  std::cout << "Usage: \n"
160  << argv[0]
161  << " --input_directory <data directory> --config_color <object.xml> --config_depth <object.xml>"
162  " --model_color <object.cao> --model_depth <object.cao> --init_file <object.init> --disable_depth"
163  << std::endl;
164  std::cout
165  << "\nExample:\n"
166  << argv[0]
167  << " --config_color model/cube/cube.xml --config_depth model/cube/cube.xml"
168  " --model_color model/cube/cube.cao --model_depth model/cube/cube.cao --init_file model/cube/cube.init\n"
169  << std::endl;
170  return EXIT_SUCCESS;
171  }
172  }
173 
174  std::cout << "Tracked features: " << std::endl;
175 #if defined(VISP_HAVE_OPENCV)
176  std::cout << " Use edges : 1" << std::endl;
177 #if defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
178  std::cout << " Use klt : 1" << std::endl;
179 #else
180  std::cout << " Use klt : 0" << std::endl;
181 #endif
182  std::cout << " Use depth : " << !disable_depth << std::endl;
183 #else
184  std::cout << " Use edges : 1" << std::endl;
185  std::cout << " Use klt : 0" << std::endl;
186  std::cout << " Use depth : 0" << std::endl;
187 #endif
188  std::cout << "Config files: " << std::endl;
189  std::cout << " Input directory: "
190  << "\"" << input_directory << "\"" << std::endl;
191  std::cout << " Config color: "
192  << "\"" << config_color << "\"" << std::endl;
193  std::cout << " Config depth: "
194  << "\"" << config_depth << "\"" << std::endl;
195  std::cout << " Model color : "
196  << "\"" << model_color << "\"" << std::endl;
197  std::cout << " Model depth : "
198  << "\"" << model_depth << "\"" << std::endl;
199  std::cout << " Init file : "
200  << "\"" << init_file << "\"" << std::endl;
201 
202  vpImage<vpRGBa> I_color;
204  vpImage<unsigned char> I_gray, I_depth;
206  vpImage<uint16_t> I_depth_raw;
208  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
210  vpCameraParameters cam_color, cam_depth;
211 
212  read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
213  vpImageConvert::convert(I_color, I_gray);
214  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
215 
216 #if defined(VISP_HAVE_X11)
217  vpDisplayX d1, d2;
218 #elif defined(VISP_HAVE_GDI)
219  vpDisplayGDI d1, d2;
220 #endif
221 
222 #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)
223  unsigned int _posx = 100, _posy = 50, _posdx = 10;
224  d1.init(I_gray, _posx, _posy, "Color stream");
225  d2.init(I_depth, _posx + I_gray.getWidth() + _posdx, _posy, "Depth stream");
226 #endif
227 
228  vpDisplay::display(I_gray);
229  vpDisplay::display(I_depth);
230  vpDisplay::flush(I_gray);
231  vpDisplay::flush(I_depth);
232 
234  std::vector<int> trackerTypes;
235 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
237 #else
238  trackerTypes.push_back(vpMbGenericTracker::EDGE_TRACKER);
239 #endif
240  trackerTypes.push_back(vpMbGenericTracker::DEPTH_DENSE_TRACKER);
241  vpMbGenericTracker tracker(trackerTypes);
243 #if defined(VISP_HAVE_PUGIXML)
245  tracker.loadConfigFile(config_color, config_depth);
247 #else
248  {
249  vpCameraParameters cam_color, cam_depth;
250  cam_color.initPersProjWithoutDistortion(614.9, 614.9, 320.2, 241.5);
251  cam_depth.initPersProjWithoutDistortion(384.0, 384.0, 320.5, 235.6);
252  tracker.setCameraParameters(cam_color, cam_depth);
253  }
254 
255  // Edge
256  vpMe me;
257  me.setMaskSize(5);
258  me.setMaskNumber(180);
259  me.setRange(7);
261  me.setThreshold(10);
262  me.setMu1(0.5);
263  me.setMu2(0.5);
264  me.setSampleStep(4);
265  tracker.setMovingEdge(me);
266 
267  // Klt
268 #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
269  vpKltOpencv klt;
270  tracker.setKltMaskBorder(5);
271  klt.setMaxFeatures(300);
272  klt.setWindowSize(5);
273  klt.setQuality(0.01);
274  klt.setMinDistance(5);
275  klt.setHarrisFreeParameter(0.01);
276  klt.setBlockSize(3);
277  klt.setPyramidLevels(3);
278 
279  tracker.setKltOpencv(klt);
280 #endif
281 
282  // Depth
283  tracker.setDepthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION);
284  tracker.setDepthNormalPclPlaneEstimationMethod(2);
285  tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200);
286  tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001);
287  tracker.setDepthNormalSamplingStep(2, 2);
288 
289  tracker.setDepthDenseSamplingStep(4, 4);
290 
291  tracker.setAngleAppear(vpMath::rad(80.0));
292  tracker.setAngleDisappear(vpMath::rad(85.0));
293  tracker.setNearClippingDistance(0.001);
294  tracker.setFarClippingDistance(5.0);
295  tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING);
296 #endif
298  tracker.loadModel(model_color, model_depth);
300 
301  tracker.getCameraParameters(cam_color, cam_depth);
302 
303  std::cout << "Camera parameters for color camera (from XML file): " << cam_color << std::endl;
304  std::cout << "Camera parameters for depth camera (from XML file): " << cam_depth << std::endl;
305 
307  tracker.setDisplayFeatures(true);
309 
311  vpHomogeneousMatrix depth_M_color;
312  {
313  std::ifstream file((std::string(input_directory + "/depth_M_color.txt")).c_str());
314  depth_M_color.load(file);
315  file.close();
316  }
317  std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
318  mapOfCameraTransformations["Camera1"] = vpHomogeneousMatrix();
319  mapOfCameraTransformations["Camera2"] = depth_M_color;
320  tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
322  std::cout << "depth_M_color: \n" << depth_M_color << std::endl;
323 
325  std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
326  mapOfImages["Camera1"] = &I_gray;
327  mapOfImages["Camera2"] = &I_depth;
329 
331  std::map<std::string, std::string> mapOfInitFiles;
332  mapOfInitFiles["Camera1"] = init_file;
333  tracker.initClick(mapOfImages, mapOfInitFiles, true);
335 
336  mapOfImages.clear();
337  pcl::PointCloud<pcl::PointXYZ>::Ptr empty_pointcloud(new pcl::PointCloud<pcl::PointXYZ>);
338  std::vector<double> times_vec;
339 
340  try {
341  bool quit = false;
342  while (!quit) {
343  double t = vpTime::measureTimeMs();
344  quit = !read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
345  vpImageConvert::convert(I_color, I_gray);
346  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
347 
348  vpDisplay::display(I_gray);
349  vpDisplay::display(I_depth);
350 
351  mapOfImages["Camera1"] = &I_gray;
352  std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
353  if (disable_depth)
354  mapOfPointclouds["Camera2"] = empty_pointcloud;
355  else
356  mapOfPointclouds["Camera2"] = pointcloud;
357 
359  tracker.track(mapOfImages, mapOfPointclouds);
361 
363  vpHomogeneousMatrix cMo = tracker.getPose();
365 
366  std::cout << "iter: " << frame_cpt << " cMo:\n" << cMo << std::endl;
367 
369  tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth, vpColor::red, 3);
370  vpDisplay::displayFrame(I_gray, cMo, cam_color, 0.05, vpColor::none, 3);
371  vpDisplay::displayFrame(I_depth, depth_M_color * cMo, cam_depth, 0.05, vpColor::none, 3);
373 
374  t = vpTime::measureTimeMs() - t;
375  times_vec.push_back(t);
376 
377  std::stringstream ss;
378  ss << "Computation time: " << t << " ms";
379  vpDisplay::displayText(I_gray, 20, 20, ss.str(), vpColor::red);
380  {
381  std::stringstream ss;
382  ss << "Nb features: " << tracker.getError().size();
383  vpDisplay::displayText(I_gray, I_gray.getHeight() - 50, 20, ss.str(), vpColor::red);
384  }
385  {
386  std::stringstream ss;
387  ss << "Features: edges " << tracker.getNbFeaturesEdge() << ", klt " << tracker.getNbFeaturesKlt() << ", depth "
388  << tracker.getNbFeaturesDepthDense();
389  vpDisplay::displayText(I_gray, I_gray.getHeight() - 30, 20, ss.str(), vpColor::red);
390  }
391 
392  vpDisplay::flush(I_gray);
393  vpDisplay::flush(I_depth);
394 
396  if (vpDisplay::getClick(I_gray, button, false)) {
397  quit = true;
398  }
399 
400  frame_cpt++;
401  }
402  }
403  catch (const vpException &e) {
404  std::cout << "Catch exception: " << e.getStringMessage() << std::endl;
405  }
406 
407  std::cout << "\nProcessing time, Mean: " << vpMath::getMean(times_vec)
408  << " ms ; Median: " << vpMath::getMedian(times_vec) << " ; Std: " << vpMath::getStdev(times_vec) << " ms"
409  << std::endl;
410 
411  vpDisplay::displayText(I_gray, 60, 20, "Click to quit", vpColor::red);
412  vpDisplay::flush(I_gray);
413  vpDisplay::getClick(I_gray);
414 
415  return EXIT_SUCCESS;
416 }
417 #else
418 int main()
419 {
420  std::cout << "To run this tutorial, ViSP should be build with PCL library."
421  " Install libpcl, configure and build again ViSP..."
422  << std::endl;
423  return EXIT_SUCCESS;
424 }
425 #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()