Visual Servoing Platform  version 3.6.1 under development (2024-04-18)
tutorial-mb-generic-tracker-apriltag-rs2.cpp
1 #include <fstream>
3 #include <ios>
4 #include <iostream>
5 
6 #include <visp3/detection/vpDetectorAprilTag.h>
7 #include <visp3/gui/vpDisplayGDI.h>
8 #include <visp3/gui/vpDisplayOpenCV.h>
9 #include <visp3/gui/vpDisplayX.h>
10 #include <visp3/mbt/vpMbGenericTracker.h>
11 #include <visp3/sensor/vpRealSense2.h>
12 
13 typedef enum { state_detection, state_tracking, state_quit } state_t;
14 
15 // Creates a cube.cao file in your current directory
16 // cubeEdgeSize : size of cube edges in meters
17 void createCaoFile(double cubeEdgeSize)
18 {
19  std::ofstream fileStream;
20  fileStream.open("cube.cao", std::ofstream::out | std::ofstream::trunc);
21  fileStream << "V1\n";
22  fileStream << "# 3D Points\n";
23  fileStream << "8 # Number of points\n";
24  fileStream << cubeEdgeSize / 2 << " " << cubeEdgeSize / 2 << " " << 0 << " # Point 0: (X, Y, Z)\n";
25  fileStream << cubeEdgeSize / 2 << " " << -cubeEdgeSize / 2 << " " << 0 << " # Point 1\n";
26  fileStream << -cubeEdgeSize / 2 << " " << -cubeEdgeSize / 2 << " " << 0 << " # Point 2\n";
27  fileStream << -cubeEdgeSize / 2 << " " << cubeEdgeSize / 2 << " " << 0 << " # Point 3\n";
28  fileStream << -cubeEdgeSize / 2 << " " << cubeEdgeSize / 2 << " " << -cubeEdgeSize << " # Point 4\n";
29  fileStream << -cubeEdgeSize / 2 << " " << -cubeEdgeSize / 2 << " " << -cubeEdgeSize << " # Point 5\n";
30  fileStream << cubeEdgeSize / 2 << " " << -cubeEdgeSize / 2 << " " << -cubeEdgeSize << " # Point 6\n";
31  fileStream << cubeEdgeSize / 2 << " " << cubeEdgeSize / 2 << " " << -cubeEdgeSize << " # Point 7\n";
32  fileStream << "# 3D Lines\n";
33  fileStream << "0 # Number of lines\n";
34  fileStream << "# Faces from 3D lines\n";
35  fileStream << "0 # Number of faces\n";
36  fileStream << "# Faces from 3D points\n";
37  fileStream << "6 # Number of faces\n";
38  fileStream << "4 0 3 2 1 # Face 0: [number of points] [index of the 3D points]...\n";
39  fileStream << "4 1 2 5 6\n";
40  fileStream << "4 4 7 6 5\n";
41  fileStream << "4 0 7 4 3\n";
42  fileStream << "4 5 2 3 4\n";
43  fileStream << "4 0 1 6 7 # Face 5\n";
44  fileStream << "# 3D cylinders\n";
45  fileStream << "0 # Number of cylinders\n";
46  fileStream << "# 3D circles\n";
47  fileStream << "0 # Number of circles\n";
48  fileStream.close();
49 }
50 
51 #if defined(VISP_HAVE_APRILTAG)
52 state_t detectAprilTag(const vpImage<unsigned char> &I, vpDetectorAprilTag &detector, double tagSize,
53  const vpCameraParameters &cam, vpHomogeneousMatrix &cMo)
54 {
55  std::vector<vpHomogeneousMatrix> cMo_vec;
56 
57  // Detection
58  bool ret = detector.detect(I, tagSize, cam, cMo_vec);
59 
60  // Display camera pose
61  for (size_t i = 0; i < cMo_vec.size(); i++) {
62  vpDisplay::displayFrame(I, cMo_vec[i], cam, tagSize / 2, vpColor::none, 3);
63  }
64 
65  vpDisplay::displayText(I, 40, 20, "State: waiting tag detection", vpColor::red);
66 
67  if (ret && detector.getNbObjects() > 0) { // if tag detected, we pick the first one
68  cMo = cMo_vec[0];
69  return state_tracking;
70  }
71 
72  return state_detection;
73 }
74 #endif // #if defined(VISP_HAVE_APRILTAG)
75 
76 state_t track(const vpImage<unsigned char> &I, vpMbGenericTracker &tracker, double projection_error_threshold,
78 {
80  tracker.getCameraParameters(cam);
81 
82  // Track the object
83  try {
84  tracker.track(I);
85  }
86  catch (...) {
87  return state_detection;
88  }
89 
90  tracker.getPose(cMo);
91 
92  // Detect tracking error
93  double projection_error = tracker.computeCurrentProjectionError(I, cMo, cam);
94  if (projection_error > projection_error_threshold) {
95  return state_detection;
96  }
97 
98  // Display
99  tracker.display(I, cMo, cam, vpColor::red, 2);
100  vpDisplay::displayFrame(I, cMo, cam, 0.025, vpColor::none, 3);
101  vpDisplay::displayText(I, 40, 20, "State: tracking in progress", vpColor::red);
102  {
103  std::stringstream ss;
104  ss << "Features: edges " << tracker.getNbFeaturesEdge() << ", klt " << tracker.getNbFeaturesKlt();
105  vpDisplay::displayText(I, 60, 20, ss.str(), vpColor::red);
106  }
107 
108  return state_tracking;
109 }
110 
111 state_t track(std::map<std::string, const vpImage<unsigned char> *> mapOfImages,
112 #ifdef VISP_HAVE_PCL
113  std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds,
114 #else
115  std::map<std::string, const std::vector<vpColVector> *> mapOfPointclouds,
116  std::map<std::string, unsigned int> mapOfWidths, std::map<std::string, unsigned int> mapOfHeights,
117 #endif
118  const vpImage<unsigned char> &I_gray, const vpImage<unsigned char> &I_depth,
119  const vpHomogeneousMatrix &depth_M_color, vpMbGenericTracker &tracker, double projection_error_threshold,
120  vpHomogeneousMatrix &cMo)
121 {
122  vpCameraParameters cam_color, cam_depth;
123  tracker.getCameraParameters(cam_color, cam_depth);
124 
125  // Track the object
126  try {
127 #ifdef VISP_HAVE_PCL
128  tracker.track(mapOfImages, mapOfPointclouds);
129 #else
130  tracker.track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights);
131 #endif
132  }
133  catch (...) {
134  return state_detection;
135  }
136 
137  tracker.getPose(cMo);
138 
139  // Detect tracking error
140  double projection_error = tracker.computeCurrentProjectionError(I_gray, cMo, cam_color);
141  if (projection_error > projection_error_threshold) {
142  return state_detection;
143  }
144 
145  // Display
146  tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth, vpColor::red, 3);
147  vpDisplay::displayFrame(I_gray, cMo, cam_color, 0.05, vpColor::none, 3);
148  vpDisplay::displayFrame(I_depth, depth_M_color * cMo, cam_depth, 0.05, vpColor::none, 3);
149 
150  return state_tracking;
151 }
152 
153 int main(int argc, const char **argv)
154 {
156 #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_MODULE_MBT)
158 
160  double opt_tag_size = 0.08;
161  float opt_quad_decimate = 1.0;
162  int opt_nthreads = 1;
163  double opt_cube_size = 0.125; // 12.5cm by default
164 #ifdef VISP_HAVE_OPENCV
165  bool opt_use_texture = false;
166 #endif
167  bool opt_use_depth = false;
168  double opt_projection_error_threshold = 40.;
169 
170 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
171  bool display_off = true;
172 #else
173  bool display_off = false;
174 #endif
175 
176  for (int i = 1; i < argc; i++) {
177  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
178  opt_tag_size = atof(argv[i + 1]);
179  }
180  else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
181  opt_quad_decimate = (float)atof(argv[i + 1]);
182  }
183  else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) {
184  opt_nthreads = atoi(argv[i + 1]);
185  }
186  else if (std::string(argv[i]) == "--display_off") {
187  display_off = true;
188  }
189  else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) {
190  opt_tag_family = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[i + 1]);
191  }
192  else if (std::string(argv[i]) == "--cube_size" && i + 1 < argc) {
193  opt_cube_size = atof(argv[i + 1]);
194 #ifdef VISP_HAVE_OPENCV
195  }
196  else if (std::string(argv[i]) == "--texture") {
197  opt_use_texture = true;
198 #endif
199  }
200  else if (std::string(argv[i]) == "--depth") {
201  opt_use_depth = true;
202  }
203  else if (std::string(argv[i]) == "--projection_error" && i + 1 < argc) {
204  opt_projection_error_threshold = atof(argv[i + 1]);
205  }
206  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
207  std::cout << "Usage: " << argv[0]
208  << " [--cube_size <size in m>] [--tag_size <size in m>]"
209  " [--quad_decimate <decimation>] [--nthreads <nb>]"
210  " [--tag_family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, "
211  " 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>]";
212 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
213  std::cout << " [--display_off]";
214 #endif
215  std::cout << " [--texture] [--depth] [--projection_error <30 - 100>] [--help]" << std::endl;
216  return EXIT_SUCCESS;
217  }
218  }
219 
220  createCaoFile(opt_cube_size);
221 
222  try {
224  vpRealSense2 realsense;
225  rs2::config config;
226  int width = 640, height = 480, stream_fps = 30;
227  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, stream_fps);
228  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, stream_fps);
229  config.disable_stream(RS2_STREAM_INFRARED);
230  realsense.open(config);
231 
232  vpCameraParameters cam_color, cam_depth;
233  vpHomogeneousMatrix depth_M_color;
234  cam_color = realsense.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion);
235  if (opt_use_depth) {
236  cam_depth = realsense.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion);
237  depth_M_color = realsense.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH);
238  }
239 
240  vpImage<vpRGBa> I_color(height, width);
241  vpImage<unsigned char> I_gray(height, width);
242  vpImage<unsigned char> I_depth(height, width);
243  vpImage<uint16_t> I_depth_raw(height, width);
244  std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
245  std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
246 #ifdef VISP_HAVE_PCL
247  std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
248  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
249 #else
250  std::map<std::string, const std::vector<vpColVector> *> mapOfPointclouds;
251  std::map<std::string, unsigned int> mapOfWidths, mapOfHeights;
252  std::vector<vpColVector> pointcloud;
253 #endif
254 
255  std::map<std::string, vpHomogeneousMatrix> mapOfCameraPoses;
256 
257  std::cout << "Cube size: " << opt_cube_size << std::endl;
258  std::cout << "AprilTag size: " << opt_tag_size << std::endl;
259  std::cout << "AprilTag family: " << opt_tag_family << std::endl;
260  std::cout << "Camera parameters:" << std::endl;
261  std::cout << " Color:\n" << cam_color << std::endl;
262  if (opt_use_depth)
263  std::cout << " Depth:\n" << cam_depth << std::endl;
264  std::cout << "Detection: " << std::endl;
265  std::cout << " Quad decimate: " << opt_quad_decimate << std::endl;
266  std::cout << " Threads number: " << opt_nthreads << std::endl;
267  std::cout << "Tracker: " << std::endl;
268  std::cout << " Use edges : 1" << std::endl;
269  std::cout << " Use texture: "
270 #ifdef VISP_HAVE_OPENCV
271  << opt_use_texture << std::endl;
272 #else
273  << " na" << std::endl;
274 #endif
275  std::cout << " Use depth : " << opt_use_depth << std::endl;
276  std::cout << " Projection error: " << opt_projection_error_threshold << std::endl;
277 
278  // Construct display
279  vpDisplay *d_gray = nullptr;
280  vpDisplay *d_depth = nullptr;
281 
282  if (!display_off) {
283 #ifdef VISP_HAVE_X11
284  d_gray = new vpDisplayX(I_gray, 50, 50, "Color stream");
285  if (opt_use_depth)
286  d_depth = new vpDisplayX(I_depth, 80 + I_gray.getWidth(), 50, "Depth stream");
287 #elif defined(VISP_HAVE_GDI)
288  d_gray = new vpDisplayGDI(I_gray);
289  if (opt_use_depth)
290  d_depth = new vpDisplayGDI(I_depth);
291 #elif defined(HAVE_OPENCV_HIGHGUI)
292  d_gray = new vpDisplayOpenCV(I_gray);
293  if (opt_use_depth)
294  d_depth = new vpDisplayOpenCV(I_depth);
295 #endif
296  }
297 
298  // Initialize AprilTag detector
299  vpDetectorAprilTag detector(opt_tag_family);
300  detector.setAprilTagQuadDecimate(opt_quad_decimate);
301  detector.setAprilTagNbThreads(opt_nthreads);
302 
303  // Prepare MBT
304  std::vector<int> trackerTypes;
305 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
306  if (opt_use_texture)
308  else
309 #endif
310  trackerTypes.push_back(vpMbGenericTracker::EDGE_TRACKER);
311 
312  if (opt_use_depth)
313  trackerTypes.push_back(vpMbGenericTracker::DEPTH_DENSE_TRACKER);
314 
315  vpMbGenericTracker tracker(trackerTypes);
316  // edges
317  vpMe me;
318  me.setMaskSize(5);
319  me.setMaskNumber(180);
321  me.setRange(12);
324  me.setThreshold(20);
325  me.setMu1(0.5);
326  me.setMu2(0.5);
327  me.setSampleStep(4);
328  tracker.setMovingEdge(me);
329 
330 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
331  if (opt_use_texture) {
332  vpKltOpencv klt_settings;
333  klt_settings.setMaxFeatures(300);
334  klt_settings.setWindowSize(5);
335  klt_settings.setQuality(0.015);
336  klt_settings.setMinDistance(8);
337  klt_settings.setHarrisFreeParameter(0.01);
338  klt_settings.setBlockSize(3);
339  klt_settings.setPyramidLevels(3);
340  tracker.setKltOpencv(klt_settings);
341  tracker.setKltMaskBorder(5);
342  }
343 #endif
344 
345  if (opt_use_depth) {
346  // camera calibration params
347  tracker.setCameraParameters(cam_color, cam_depth);
348  // model definition
349  tracker.loadModel("cube.cao", "cube.cao");
350  mapOfCameraTransformations["Camera2"] = depth_M_color;
351  tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
352  tracker.setAngleAppear(vpMath::rad(70), vpMath::rad(70));
353  tracker.setAngleDisappear(vpMath::rad(80), vpMath::rad(80));
354  }
355  else {
356  // camera calibration params
357  tracker.setCameraParameters(cam_color);
358  // model definition
359  tracker.loadModel("cube.cao");
360  tracker.setAngleAppear(vpMath::rad(70));
361  tracker.setAngleDisappear(vpMath::rad(80));
362  }
363  tracker.setDisplayFeatures(true);
364 
366  state_t state = state_detection;
367 
368  // wait for a tag detection
369  while (state != state_quit) {
370  if (opt_use_depth) {
371 #ifdef VISP_HAVE_PCL
372  realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, nullptr, pointcloud, nullptr);
373 #else
374  realsense.acquire((unsigned char *)I_color.bitmap, (unsigned char *)I_depth_raw.bitmap, &pointcloud, nullptr,
375  nullptr);
376 #endif
377  vpImageConvert::convert(I_color, I_gray);
378  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
379  vpDisplay::display(I_gray);
380  vpDisplay::display(I_depth);
381 
382  mapOfImages["Camera1"] = &I_gray;
383  mapOfImages["Camera2"] = &I_depth;
384 #ifdef VISP_HAVE_PCL
385  mapOfPointclouds["Camera2"] = pointcloud;
386 #else
387  mapOfPointclouds["Camera2"] = &pointcloud;
388  mapOfWidths["Camera2"] = width;
389  mapOfHeights["Camera2"] = height;
390 #endif
391  }
392  else {
393  realsense.acquire(I_gray);
394  vpDisplay::display(I_gray);
395  }
396 
397  if (state == state_detection) {
398  state = detectAprilTag(I_gray, detector, opt_tag_size, cam_color, cMo);
399 
400  // Initialize the tracker with the result of the detection
401  if (state == state_tracking) {
402  if (opt_use_depth) {
403  mapOfCameraPoses["Camera1"] = cMo;
404  mapOfCameraPoses["Camera2"] = depth_M_color * cMo;
405  tracker.initFromPose(mapOfImages, mapOfCameraPoses);
406  }
407  else {
408  tracker.initFromPose(I_gray, cMo);
409  }
410  }
411  }
412 
413  if (state == state_tracking) {
414  if (opt_use_depth) {
415 #ifdef VISP_HAVE_PCL
416  state = track(mapOfImages, mapOfPointclouds, I_gray, I_depth, depth_M_color, tracker,
417  opt_projection_error_threshold, cMo);
418 #else
419  state = track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights, I_gray, I_depth, depth_M_color,
420  tracker, opt_projection_error_threshold, cMo);
421 #endif
422  }
423  else {
424  state = track(I_gray, tracker, opt_projection_error_threshold, cMo);
425  }
426  {
427  std::stringstream ss;
428  ss << "Features: edges " << tracker.getNbFeaturesEdge() << ", klt " << tracker.getNbFeaturesKlt()
429  << ", depth " << tracker.getNbFeaturesDepthDense();
430  vpDisplay::displayText(I_gray, I_gray.getHeight() - 30, 20, ss.str(), vpColor::red);
431  }
432  }
433 
434  vpDisplay::displayText(I_gray, 20, 20, "Click to quit...", vpColor::red);
435  if (vpDisplay::getClick(I_gray, false)) { // exit
436  state = state_quit;
437  }
438  vpDisplay::flush(I_gray);
439 
440  if (opt_use_depth) {
441  vpDisplay::displayText(I_depth, 20, 20, "Click to quit...", vpColor::red);
442  if (vpDisplay::getClick(I_depth, false)) { // exit
443  state = state_quit;
444  }
445  vpDisplay::flush(I_depth);
446  }
447  }
448 
449  if (!display_off) {
450  delete d_gray;
451  if (opt_use_depth)
452  delete d_depth;
453  }
454  }
455  catch (const vpException &e) {
456  std::cerr << "Catch an exception: " << e.getMessage() << std::endl;
457  }
458 
459  return EXIT_SUCCESS;
460 #else
461  (void)argc;
462  (void)argv;
463 #ifndef VISP_HAVE_APRILTAG
464  std::cout << "ViSP is not build with Apriltag support" << std::endl;
465 #endif
466 #ifndef VISP_HAVE_REALSENSE2
467  std::cout << "ViSP is not build with librealsense2 support" << std::endl;
468 #endif
469  std::cout << "Install missing 3rd parties, configure and build ViSP to run this tutorial" << std::endl;
470 #endif
471  return EXIT_SUCCESS;
472 }
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor red
Definition: vpColor.h:211
static const vpColor none
Definition: vpColor.h:223
void setAprilTagQuadDecimate(float quadDecimate)
bool detect(const vpImage< unsigned char > &I) vp_override
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
void setAprilTagNbThreads(int nThreads)
size_t getNbObjects() const
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
Class that defines generic functionalities for display.
Definition: vpDisplay.h:173
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 char * getMessage() const
Definition: vpException.cpp:64
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
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
Real-time 6D object pose tracking using its CAD model.
virtual void initFromPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo) vp_override
virtual void setKltMaskBorder(const unsigned int &e)
virtual unsigned int getNbFeaturesEdge() const
virtual void setAngleDisappear(const double &a) vp_override
virtual void getPose(vpHomogeneousMatrix &cMo) const vp_override
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false) vp_override
virtual void getCameraParameters(vpCameraParameters &camera) const vp_override
virtual unsigned int getNbFeaturesKlt() const
virtual void setMovingEdge(const vpMe &me)
virtual void setAngleAppear(const double &a) vp_override
virtual unsigned int getNbFeaturesDepthDense() const
virtual void loadModel(const std::string &modelFile, bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix()) vp_override
virtual void setKltOpencv(const vpKltOpencv &t)
virtual void setCameraParameters(const vpCameraParameters &camera) vp_override
virtual double computeCurrentProjectionError(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &_cMo, const vpCameraParameters &_cam) vp_override
virtual void setDisplayFeatures(bool displayF) vp_override
virtual void setCameraTransformationMatrix(const std::string &cameraName, const vpHomogeneousMatrix &cameraTransformationMatrix)
virtual void track(const vpImage< unsigned char > &I) vp_override
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
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const