Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
tutorial-mb-generic-tracker-apriltag-live-realsense2.cpp
1 #include <fstream>
3 #include <ios>
4 #include <iostream>
5 
6 #include <visp3/gui/vpDisplayGDI.h>
7 #include <visp3/gui/vpDisplayOpenCV.h>
8 #include <visp3/gui/vpDisplayX.h>
9 #include <visp3/core/vpXmlParserCamera.h>
10 #include <visp3/sensor/vpRealSense2.h>
11 #include <visp3/detection/vpDetectorAprilTag.h>
12 #include <visp3/mbt/vpMbGenericTracker.h>
13 
14 typedef enum {
15  state_detection,
16  state_tracking,
17  state_quit
18 } 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,
58  double tagSize, 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,
82  double projection_error_threshold, vpHomogeneousMatrix &cMo)
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  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,
117  std::map<std::string, unsigned int> mapOfHeights,
118  #endif
119  const vpImage<unsigned char> &I_gray,
120  const vpImage<unsigned char> &I_depth,
121  const vpHomogeneousMatrix &depth_M_color,
122  vpMbGenericTracker &tracker,
123  double projection_error_threshold, vpHomogeneousMatrix &cMo)
124 {
125  vpCameraParameters cam_color, cam_depth;
126  tracker.getCameraParameters(cam_color, cam_depth);
127 
128  // Track the object
129  try {
130 #ifdef VISP_HAVE_PCL
131  tracker.track(mapOfImages, mapOfPointclouds);
132 #else
133  tracker.track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights);
134 #endif
135  }
136  catch (...) {
137  return state_detection;
138  }
139 
140  tracker.getPose(cMo);
141 
142  // Detect tracking error
143  double projection_error = tracker.computeCurrentProjectionError(I_gray, cMo, cam_color);
144  if (projection_error > projection_error_threshold) {
145  return state_detection;
146  }
147 
148  // Display
149  tracker.display(I_gray, I_depth, cMo, depth_M_color*cMo, cam_color, cam_depth, vpColor::red, 3);
150  vpDisplay::displayFrame(I_gray, cMo, cam_color, 0.05, vpColor::none, 3);
151  vpDisplay::displayFrame(I_depth, depth_M_color*cMo, cam_depth, 0.05, vpColor::none, 3);
152 
153  return state_tracking;
154 }
155 
156 int main(int argc, const char **argv)
157 {
159 #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_MODULE_MBT)
160 
163  double opt_tag_size = 0.08;
164  float opt_quad_decimate = 1.0;
165  int opt_nthreads = 1;
166  double opt_cube_size = 0.125; // 12.5cm by default
167 #ifdef VISP_HAVE_OPENCV
168  bool opt_use_texture = false;
169 #endif
170  bool opt_use_depth = false;
171  double opt_projection_error_threshold = 40.;
172 
173 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
174  bool display_off = true;
175 #else
176  bool display_off = false;
177 #endif
178 
179  for (int i = 1; i < argc; i++) {
180  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
181  opt_tag_size = atof(argv[i + 1]);
182  } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
183  opt_quad_decimate = (float)atof(argv[i + 1]);
184  } else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) {
185  opt_nthreads = atoi(argv[i + 1]);
186  } else if (std::string(argv[i]) == "--display_off") {
187  display_off = true;
188  } else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) {
189  opt_tag_family = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[i + 1]);
190  } else if (std::string(argv[i]) == "--cube_size" && i + 1 < argc) {
191  opt_cube_size = atof(argv[i + 1]);
192 #ifdef VISP_HAVE_OPENCV
193  } else if (std::string(argv[i]) == "--texture") {
194  opt_use_texture = true;
195 #endif
196  } else if (std::string(argv[i]) == "--depth") {
197  opt_use_depth = true;
198  } else if (std::string(argv[i]) == "--projection_error" && i + 1 < argc) {
199  opt_projection_error_threshold = atof(argv[i + 1]);
200  } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
201  std::cout << "Usage: " << argv[0] << " [--cube_size <size in m>] [--tag_size <size in m>]"
202  " [--quad_decimate <decimation>] [--nthreads <nb>]"
203  " [--tag_family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, "
204  " 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>]";
205 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
206  std::cout << " [--display_off]";
207 #endif
208  std::cout << " [--texture] [--depth] [--projection_error <30 - 100>] [--help]" << std::endl;
209  return EXIT_SUCCESS;
210  }
211  }
212 
213  createCaoFile(opt_cube_size);
214 
215  try {
217  vpRealSense2 realsense;
218  rs2::config config;
219  int width = 640, height = 480, stream_fps = 30;
220  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, stream_fps);
221  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, stream_fps);
222  config.disable_stream(RS2_STREAM_INFRARED);
223  realsense.open(config);
224 
225  vpCameraParameters cam_color, cam_depth;
226  vpHomogeneousMatrix depth_M_color;
227  cam_color = realsense.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion);
228  if (opt_use_depth) {
229  cam_depth = realsense.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion);
230  depth_M_color = realsense.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH);
231  }
232 
233  vpImage<vpRGBa> I_color(height, width);
234  vpImage<unsigned char> I_gray(height, width);
235  vpImage<unsigned char> I_depth(height, width);
236  vpImage<uint16_t> I_depth_raw(height, width);
237  std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
238  std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
239 #ifdef VISP_HAVE_PCL
240  std::map<std::string, pcl::PointCloud< pcl::PointXYZ >::ConstPtr> mapOfPointclouds;
241  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
242 #else
243  std::map<std::string, const std::vector<vpColVector> *> mapOfPointclouds;
244  std::map<std::string, unsigned int> mapOfWidths, mapOfHeights;
245  std::vector<vpColVector> pointcloud;
246 #endif
247 
248  std::map<std::string, vpHomogeneousMatrix> mapOfCameraPoses;
249 
250  std::cout << "Cube size: " << opt_cube_size << std::endl;
251  std::cout << "AprilTag size: " << opt_tag_size << std::endl;
252  std::cout << "AprilTag family: " << opt_tag_family << std::endl;
253  std::cout << "Camera parameters:" << std::endl;
254  std::cout << " Color:\n" << cam_color << std::endl;
255  if (opt_use_depth)
256  std::cout << " Depth:\n" << cam_depth << std::endl;
257  std::cout << "Detection: " << std::endl;
258  std::cout << " Quad decimate: " << opt_quad_decimate << std::endl;
259  std::cout << " Threads number: " << opt_nthreads << std::endl;
260  std::cout << "Tracker: " << std::endl;
261  std::cout << " Use edges : 1" << std::endl;
262  std::cout << " Use texture: "
263 #ifdef VISP_HAVE_OPENCV
264  << opt_use_texture << std::endl;
265 #else
266  << " na" << std::endl;
267 #endif
268  std::cout << " Use depth : " << opt_use_depth << std::endl;
269  std::cout << " Projection error: " << opt_projection_error_threshold << std::endl;
270 
271  // Construct display
272  vpDisplay *d_gray = NULL;
273  vpDisplay *d_depth = NULL;
274 
275  if (!display_off) {
276 #ifdef VISP_HAVE_X11
277  d_gray = new vpDisplayX(I_gray, 50, 50, "Color stream");
278  if (opt_use_depth)
279  d_depth = new vpDisplayX(I_depth, 80+I_gray.getWidth(), 50, "Depth stream");
280 #elif defined(VISP_HAVE_GDI)
281  d_gray = new vpDisplayGDI(I_gray);
282  if (opt_use_depth)
283  d_depth = new vpDisplayGDI(I_depth);
284 #elif defined(VISP_HAVE_OPENCV)
285  d_gray = new vpDisplayOpenCV(I_gray);
286  if (opt_use_depth)
287  d_depth = new vpDisplayOpenCV(I_depth);
288 #endif
289  }
290 
291  // Initialize AprilTag detector
292  vpDetectorAprilTag detector(opt_tag_family);
293  detector.setAprilTagQuadDecimate(opt_quad_decimate);
294  detector.setAprilTagNbThreads(opt_nthreads);
295 
296  // Prepare MBT
297  std::vector<int> trackerTypes;
298 #ifdef VISP_HAVE_OPENCV
299  if (opt_use_texture)
301  else
302 #endif
303  trackerTypes.push_back(vpMbGenericTracker::EDGE_TRACKER );
304 
305  if (opt_use_depth)
306  trackerTypes.push_back(vpMbGenericTracker::DEPTH_DENSE_TRACKER);
307 
308  vpMbGenericTracker tracker(trackerTypes);
309  // edges
310  vpMe me;
311  me.setMaskSize(5);
312  me.setMaskNumber(180);
314  me.setRange(12);
316  me.setThreshold(10000);
317  me.setMu1(0.5);
318  me.setMu2(0.5);
319  me.setSampleStep(4);
320  tracker.setMovingEdge(me);
321 
322 #ifdef VISP_HAVE_OPENCV
323  if (opt_use_texture) {
324  vpKltOpencv klt_settings;
325  klt_settings.setMaxFeatures(300);
326  klt_settings.setWindowSize(5);
327  klt_settings.setQuality(0.015);
328  klt_settings.setMinDistance(8);
329  klt_settings.setHarrisFreeParameter(0.01);
330  klt_settings.setBlockSize(3);
331  klt_settings.setPyramidLevels(3);
332  tracker.setKltOpencv(klt_settings);
333  tracker.setKltMaskBorder(5);
334  }
335 #endif
336 
337  if (opt_use_depth) {
338  // camera calibration params
339  tracker.setCameraParameters(cam_color, cam_depth);
340  // model definition
341  tracker.loadModel("cube.cao", "cube.cao");
342  mapOfCameraTransformations["Camera2"] = depth_M_color;
343  tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
344  tracker.setAngleAppear(vpMath::rad(70), vpMath::rad(70));
345  tracker.setAngleDisappear(vpMath::rad(80), vpMath::rad(80));
346  }
347  else {
348  // camera calibration params
349  tracker.setCameraParameters(cam_color);
350  // model definition
351  tracker.loadModel("cube.cao");
352  tracker.setAngleAppear(vpMath::rad(70));
353  tracker.setAngleDisappear(vpMath::rad(80));
354  }
355  tracker.setDisplayFeatures(true);
356 
358  state_t state = state_detection;
359 
360  // wait for a tag detection
361  while (state != state_quit) {
362  if (opt_use_depth) {
363 #ifdef VISP_HAVE_PCL
364  realsense.acquire((unsigned char *) I_color.bitmap, (unsigned char *) I_depth_raw.bitmap, NULL, pointcloud, NULL);
365 #else
366  realsense.acquire((unsigned char *) I_color.bitmap, (unsigned char *) I_depth_raw.bitmap, &pointcloud, NULL, NULL);
367 #endif
368  vpImageConvert::convert(I_color, I_gray);
369  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
370  vpDisplay::display(I_gray);
371  vpDisplay::display(I_depth);
372 
373  mapOfImages["Camera1"] = &I_gray;
374  mapOfImages["Camera2"] = &I_depth;
375 #ifdef VISP_HAVE_PCL
376  mapOfPointclouds["Camera2"] = pointcloud;
377 #else
378  mapOfPointclouds["Camera2"] = &pointcloud;
379  mapOfWidths["Camera2"] = width;
380  mapOfHeights["Camera2"] = height;
381 #endif
382  }
383  else {
384  realsense.acquire(I_gray);
385  vpDisplay::display(I_gray);
386  }
387 
388  if (state == state_detection) {
389  state = detectAprilTag(I_gray, detector, opt_tag_size, cam_color, cMo);
390 
391  // Initialize the tracker with the result of the detection
392  if (state == state_tracking) {
393  if (opt_use_depth) {
394  mapOfCameraPoses["Camera1"] = cMo;
395  mapOfCameraPoses["Camera2"] = depth_M_color * cMo;
396  tracker.initFromPose(mapOfImages, mapOfCameraPoses);
397  }
398  else {
399  tracker.initFromPose(I_gray, cMo);
400  }
401  }
402  }
403 
404  if (state == state_tracking) {
405  if (opt_use_depth) {
406 #ifdef VISP_HAVE_PCL
407  state = track(mapOfImages, mapOfPointclouds,
408  I_gray, I_depth, depth_M_color, tracker, opt_projection_error_threshold, cMo);
409 #else
410  state = track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights,
411  I_gray, I_depth, depth_M_color, tracker, opt_projection_error_threshold, cMo);
412 #endif
413  }
414  else {
415  state = track(I_gray, tracker, opt_projection_error_threshold, cMo);
416  }
417  }
418 
419  vpDisplay::displayText(I_gray, 20, 20, "Click to quit...", vpColor::red);
420  if (vpDisplay::getClick(I_gray, false)) { // exit
421  state = state_quit;
422  }
423  vpDisplay::flush(I_gray);
424 
425  if (opt_use_depth) {
426  vpDisplay::displayText(I_depth, 20, 20, "Click to quit...", vpColor::red);
427  if (vpDisplay::getClick(I_depth, false)) { // exit
428  state = state_quit;
429  }
430  vpDisplay::flush(I_depth);
431  }
432  }
433 
434  if (!display_off) {
435  delete d_gray;
436  if (opt_use_depth)
437  delete d_depth;
438  }
439  } catch (const vpException &e) {
440  std::cerr << "Catch an exception: " << e.getMessage() << std::endl;
441  }
442 
443  return EXIT_SUCCESS;
444 #else
445  (void)argc;
446  (void)argv;
447 #ifndef VISP_HAVE_APRILTAG
448  std::cout << "ViSP is not build with Apriltag support" << std::endl;
449 #endif
450 #ifndef VISP_HAVE_REALSENSE2
451  std::cout << "ViSP is not build with librealsense2 support" << std::endl;
452 #endif
453  std::cout << "Install missing 3rd parties, configure and build ViSP to run this tutorial" << std::endl;
454 #endif
455  return EXIT_SUCCESS;
456 }
virtual void setDisplayFeatures(const bool displayF)
void setAprilTagQuadDecimate(const float quadDecimate)
Class that defines generic functionnalities for display.
Definition: vpDisplay.h:171
virtual void track(const vpImage< unsigned char > &I)
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void setHarrisFreeParameter(double harris_k)
unsigned int getWidth() const
Definition: vpImage.h:239
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setMaskNumber(const unsigned int &a)
Definition: vpMe.cpp:454
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:129
void setMaxFeatures(const int maxCount)
void setSampleStep(const double &s)
Definition: vpMe.h:278
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
static const vpColor none
Definition: vpColor.h:192
void setMinDistance(double minDistance)
virtual void setAngleDisappear(const double &a)
error that can be emited by ViSP classes.
Definition: vpException.h:71
Definition: vpMe.h:60
virtual void getCameraParameters(vpCameraParameters &cam1, vpCameraParameters &cam2) const
void open(const rs2::config &cfg=rs2::config())
virtual void setMovingEdge(const vpMe &me)
size_t getNbObjects() const
Real-time 6D object pose tracking using its CAD model.
static void flush(const vpImage< unsigned char > &I)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
void setMu1(const double &mu_1)
Definition: vpMe.h:241
static const vpColor red
Definition: vpColor.h:180
void setQuality(double qualityLevel)
virtual void setKltMaskBorder(const unsigned int &e)
virtual void initFromPose(const vpImage< unsigned char > &I1, const vpImage< unsigned char > &I2, const std::string &initFile1, const std::string &initFile2)
void setMaskSize(const unsigned int &a)
Definition: vpMe.cpp:461
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, const unsigned int thickness=1, const bool displayFullModel=false)
static void display(const vpImage< unsigned char > &I)
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Generic class defining intrinsic camera parameters.
virtual void setAngleAppear(const double &a)
const char * getMessage(void) const
Definition: vpException.cpp:90
void acquire(vpImage< unsigned char > &grey)
void setPyramidLevels(const int pyrMaxLevel)
static double rad(double deg)
Definition: vpMath.h:102
virtual void loadModel(const std::string &modelFile, const bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix())
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
virtual void setCameraParameters(const vpCameraParameters &camera)
void setMu2(const double &mu_2)
Definition: vpMe.h:248
void setWindowSize(const int winSize)
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))
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
Definition: vpKltOpencv.h:78
void setBlockSize(const int blockSize)
virtual void getPose(vpHomogeneousMatrix &c1Mo, vpHomogeneousMatrix &c2Mo) const
void setThreshold(const double &t)
Definition: vpMe.h:300
void setRange(const unsigned int &r)
Definition: vpMe.h:271
virtual void setKltOpencv(const vpKltOpencv &t)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
virtual void setCameraTransformationMatrix(const std::string &cameraName, const vpHomogeneousMatrix &cameraTransformationMatrix)
void setAprilTagNbThreads(const int nThreads)
bool detect(const vpImage< unsigned char > &I)
virtual double computeCurrentProjectionError(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &_cMo, const vpCameraParameters &_cam)