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