Visual Servoing Platform  version 3.6.1 under development (2025-02-05)
tutorial-apriltag-detector-live.cpp
1 #include <iostream>
3 
4 #include <visp3/core/vpConfig.h>
5 
7 // Comment / uncomment following lines to use the specific 3rd party compatible with your camera
8 // #undef VISP_HAVE_V4L2
9 // #undef VISP_HAVE_DC1394
10 // #undef VISP_HAVE_CMU1394
11 // #undef VISP_HAVE_FLYCAPTURE
12 // #undef VISP_HAVE_REALSENSE2
13 // #undef HAVE_OPENCV_HIGHGUI
14 // #undef HAVE_OPENCV_VIDEOIO
16 
18 #if defined(VISP_HAVE_APRILTAG) && \
19  (defined(VISP_HAVE_V4L2) || defined(VISP_HAVE_DC1394) || defined(VISP_HAVE_CMU1394) || \
20  defined(VISP_HAVE_FLYCAPTURE) || defined(VISP_HAVE_REALSENSE2) || \
21  ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI)) || \
22  ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_VIDEOIO)))
23 
25 
26 #ifdef VISP_HAVE_MODULE_SENSOR
27 #include <visp3/sensor/vp1394CMUGrabber.h>
28 #include <visp3/sensor/vp1394TwoGrabber.h>
29 #include <visp3/sensor/vpFlyCaptureGrabber.h>
30 #include <visp3/sensor/vpRealSense2.h>
31 #include <visp3/sensor/vpV4l2Grabber.h>
32 #endif
34 #include <visp3/detection/vpDetectorAprilTag.h>
36 #include <visp3/core/vpXmlParserCamera.h>
37 #include <visp3/gui/vpDisplayGDI.h>
38 #include <visp3/gui/vpDisplayOpenCV.h>
39 #include <visp3/gui/vpDisplayX.h>
40 
41 #if (VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI)
42 #include <opencv2/highgui/highgui.hpp> // for cv::VideoCapture
43 #elif (VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_VIDEOIO)
44 #include <opencv2/videoio/videoio.hpp>
45 #endif
46 
47 int main(int argc, const char **argv)
48 {
49 #ifdef ENABLE_VISP_NAMESPACE
50  using namespace VISP_NAMESPACE_NAME;
51 #endif
52 
53  int opt_device = 0; // For OpenCV and V4l2 grabber to set the camera device
56  double tagSize = 0.053;
57  float quad_decimate = 1.0;
58  int nThreads = 1;
59  std::string intrinsic_file = "";
60  std::string camera_name = "";
61  bool display_tag = false;
62  int color_id = -1;
63  unsigned int thickness = 2;
64  bool align_frame = false;
65 
66 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI))
67  bool display_off = true;
68  std::cout << "Warning: There is no 3rd party (X11, GDI or openCV) to dislay images..." << std::endl;
69 #else
70  bool display_off = false;
71 #endif
72 
74 
75  for (int i = 1; i < argc; i++) {
76  if (std::string(argv[i]) == "--pose-method" && i + 1 < argc) {
77  poseEstimationMethod = (vpDetectorAprilTag::vpPoseEstimationMethod)atoi(argv[++i]);
78  }
79  else if (std::string(argv[i]) == "--tag-size" && i + 1 < argc) {
80  tagSize = atof(argv[++i]);
81  }
82  else if (std::string(argv[i]) == "--camera-device" && i + 1 < argc) {
83  opt_device = atoi(argv[++i]);
84  }
85  else if (std::string(argv[i]) == "--quad-decimate" && i + 1 < argc) {
86  quad_decimate = (float)atof(argv[++i]);
87  }
88  else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) {
89  nThreads = atoi(argv[++i]);
90  }
91  else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) {
92  intrinsic_file = std::string(argv[++i]);
93  }
94  else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) {
95  camera_name = std::string(argv[++i]);
96  }
97  else if (std::string(argv[i]) == "--display-tag") {
98  display_tag = true;
99  }
100  else if (std::string(argv[i]) == "--display-off") {
101  display_off = true;
102  }
103  else if (std::string(argv[i]) == "--color" && i + 1 < argc) {
104  color_id = atoi(argv[++i]);
105  }
106  else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) {
107  thickness = (unsigned int)atoi(argv[++i]);
108  }
109  else if (std::string(argv[i]) == "--tag-family" && i + 1 < argc) {
110  tagFamily = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[++i]);
111  }
112  else if (std::string(argv[i]) == "--z-aligned") {
113  align_frame = true;
114  }
115  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
116  std::cout << "Usage: " << argv[0] << " [--camera-device <camera device> (default: 0)]"
117  << " [--tag-size <tag_size in m> (default: 0.053)]"
118  << " [--quad-decimate <quad_decimate> (default: 1)]"
119  << " [--nthreads <nb> (default: 1)]"
120  << " [--intrinsic <intrinsic file> (default: empty)]"
121  << " [--camera-name <camera name> (default: empty)]"
122  << " [--pose-method <method> (0: HOMOGRAPHY, 1: HOMOGRAPHY_VIRTUAL_VS, "
123  << " 2: DEMENTHON_VIRTUAL_VS, 3: LAGRANGE_VIRTUAL_VS, "
124  << " 4: BEST_RESIDUAL_VIRTUAL_VS, 5: HOMOGRAPHY_ORTHOGONAL_ITERATION) (default: 0)]"
125  << " [--tag-family <family> (0: TAG_36h11, 1: TAG_36h10 (DEPRECATED), 2: TAG_36ARTOOLKIT (DEPRECATED),"
126  << " 3: TAG_25h9, 4: TAG_25h7 (DEPRECATED), 5: TAG_16h5, 6: TAG_CIRCLE21h7, 7: TAG_CIRCLE49h12,"
127  << " 8: TAG_CUSTOM48h12, 9: TAG_STANDARD41h12, 10: TAG_STANDARD52h13) (default: 0)]"
128  << " [--display-tag] [--z-aligned]";
129 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
130  std::cout << " [--display-off] [--color <color id>] [--thickness <line thickness>]";
131 #endif
132  std::cout << " [--help,-h]" << std::endl;
133  return EXIT_SUCCESS;
134  }
135  }
136 
137  try {
138  vpCameraParameters cam;
139  cam.initPersProjWithoutDistortion(615.1674805, 615.1675415, 312.1889954, 243.4373779);
140 #if defined(VISP_HAVE_PUGIXML)
141  vpXmlParserCamera parser;
142  if (!intrinsic_file.empty() && !camera_name.empty())
143  parser.parse(cam, intrinsic_file, camera_name, vpCameraParameters::perspectiveProjWithoutDistortion);
144 #endif
145 
147 #if defined(VISP_HAVE_V4L2)
148  vpV4l2Grabber g;
149  std::ostringstream device;
150  device << "/dev/video" << opt_device;
151  std::cout << "Use Video 4 Linux grabber on device " << device.str() << std::endl;
152  g.setDevice(device.str());
153  g.setScale(1);
154  g.open(I);
155 #elif defined(VISP_HAVE_DC1394)
156  (void)opt_device; // To avoid non used warning
157  std::cout << "Use DC1394 grabber" << std::endl;
159  g.open(I);
160 #elif defined(VISP_HAVE_CMU1394)
161  (void)opt_device; // To avoid non used warning
162  std::cout << "Use CMU1394 grabber" << std::endl;
164  g.open(I);
165 #elif defined(VISP_HAVE_FLYCAPTURE)
166  (void)opt_device; // To avoid non used warning
167  std::cout << "Use FlyCapture grabber" << std::endl;
169  g.open(I);
170 #elif defined(VISP_HAVE_REALSENSE2)
171  (void)opt_device; // To avoid non used warning
172  std::cout << "Use Realsense 2 grabber" << std::endl;
173  vpRealSense2 g;
174  rs2::config config;
175  config.disable_stream(RS2_STREAM_DEPTH);
176  config.disable_stream(RS2_STREAM_INFRARED);
177  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
178  g.open(config);
179  g.acquire(I);
180 
181  std::cout << "Read camera parameters from Realsense device" << std::endl;
183 #elif ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI)) || ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_VIDEOIO))
184  std::cout << "Use OpenCV grabber on device " << opt_device << std::endl;
185  cv::VideoCapture g(opt_device); // Open the default camera
186  if (!g.isOpened()) { // Check if we succeeded
187  std::cout << "Failed to open the camera" << std::endl;
188  return EXIT_FAILURE;
189  }
190  cv::Mat frame;
191  g >> frame; // get a new frame from camera
192  vpImageConvert::convert(frame, I);
193 #endif
195 
196  std::cout << cam << std::endl;
197  std::cout << "poseEstimationMethod: " << poseEstimationMethod << std::endl;
198  std::cout << "tagFamily: " << tagFamily << std::endl;
199  std::cout << "nThreads : " << nThreads << std::endl;
200  std::cout << "Z aligned: " << align_frame << std::endl;
201 
202  vpDisplay *d = nullptr;
203  if (!display_off) {
204 #ifdef VISP_HAVE_X11
205  d = new vpDisplayX(I);
206 #elif defined(VISP_HAVE_GDI)
207  d = new vpDisplayGDI(I);
208 #elif defined(HAVE_OPENCV_HIGHGUI)
209  d = new vpDisplayOpenCV(I);
210 #endif
211  }
212 
214  vpDetectorAprilTag detector(tagFamily);
216 
218  detector.setAprilTagQuadDecimate(quad_decimate);
219  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
220  detector.setAprilTagNbThreads(nThreads);
221  detector.setDisplayTag(display_tag, color_id < 0 ? vpColor::none : vpColor::getColor(color_id), thickness);
222  detector.setZAlignedWithCameraAxis(align_frame);
224 
225  std::vector<double> time_vec;
226  for (;;) {
228 #if defined(VISP_HAVE_V4L2) || defined(VISP_HAVE_DC1394) || defined(VISP_HAVE_CMU1394) || \
229  defined(VISP_HAVE_FLYCAPTURE) || defined(VISP_HAVE_REALSENSE2)
230  g.acquire(I);
231 #elif ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI)) || ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_VIDEOIO))
232  g >> frame;
233  vpImageConvert::convert(frame, I);
234 #endif
236 
238 
239  double t = vpTime::measureTimeMs();
241  std::vector<vpHomogeneousMatrix> cMo_vec;
242  detector.detect(I, tagSize, cam, cMo_vec);
244  t = vpTime::measureTimeMs() - t;
245  time_vec.push_back(t);
246 
247  std::stringstream ss;
248  ss << "Detection time: " << t << " ms for " << detector.getNbObjects() << " tags";
249  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
250 
252  for (size_t i = 0; i < cMo_vec.size(); i++) {
253  vpDisplay::displayFrame(I, cMo_vec[i], cam, tagSize / 2, vpColor::none, 3);
254  }
256 
257  vpDisplay::displayText(I, 20, 20, "Click to quit.", vpColor::red);
258  vpDisplay::flush(I);
259  if (vpDisplay::getClick(I, false))
260  break;
261  }
262 
263  std::cout << "Benchmark computation time" << std::endl;
264  std::cout << "Mean / Median / Std: " << vpMath::getMean(time_vec) << " ms"
265  << " ; " << vpMath::getMedian(time_vec) << " ms"
266  << " ; " << vpMath::getStdev(time_vec) << " ms" << std::endl;
267 
268  if (!display_off)
269  delete d;
270 
271  }
272  catch (const vpException &e) {
273  std::cerr << "Catch an exception: " << e.getMessage() << std::endl;
274  }
275 
276  return EXIT_SUCCESS;
277 }
278 
279 #else
280 
281 int main()
282 {
283 #ifndef VISP_HAVE_APRILTAG
284  std::cout << "Enable Apriltag support, configure and build ViSP to run this tutorial" << std::endl;
285 #else
286  std::cout << "Install a 3rd party dedicated to frame grabbing (dc1394, cmu1394, v4l2, OpenCV, FlyCapture, "
287  << "Realsense2), configure and build ViSP again to use this example"
288  << std::endl;
289 #endif
290  return EXIT_SUCCESS;
291 }
292 
293 #endif
Firewire cameras video capture based on CMU 1394 Digital Camera SDK.
void open(vpImage< unsigned char > &I)
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void open(vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static vpColor getColor(const unsigned int &i)
Definition: vpColor.h:292
static const vpColor red
Definition: vpColor.h:198
static const vpColor none
Definition: vpColor.h:210
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
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
void open(vpImage< unsigned char > &I)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:322
static double getStdev(const std::vector< double > &v, bool useBesselCorrection=false)
Definition: vpMath.cpp:353
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:302
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())
Class that is a wrapper over the Video4Linux2 (V4L2) driver.
void open(vpImage< unsigned char > &I)
void setScale(unsigned scale=vpV4l2Grabber::DEFAULT_SCALE)
void setDevice(const std::string &devname)
XML parser to load and save intrinsic camera parameters.
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, unsigned int image_width=0, unsigned int image_height=0, bool verbose=true)
VISP_EXPORT double measureTimeMs()