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