Visual Servoing Platform  version 3.6.1 under development (2024-05-03)
servoPixhawkDroneIBVS.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Example that shows how to do visual servoing with a drone equipped with a Pixhawk.
33  *
34 *****************************************************************************/
35 
36 #include <iostream>
37 
38 #include <visp3/core/vpConfig.h>
39 
40 // Check if std:c++17 or higher
41 #if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \
42  defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_PUGIXML)
43 
44 #include <visp3/core/vpImageConvert.h>
45 #include <visp3/core/vpMomentAreaNormalized.h>
46 #include <visp3/core/vpMomentBasic.h>
47 #include <visp3/core/vpMomentCentered.h>
48 #include <visp3/core/vpMomentDatabase.h>
49 #include <visp3/core/vpMomentGravityCenter.h>
50 #include <visp3/core/vpMomentGravityCenterNormalized.h>
51 #include <visp3/core/vpMomentObject.h>
52 #include <visp3/core/vpPixelMeterConversion.h>
53 #include <visp3/core/vpPoint.h>
54 #include <visp3/core/vpTime.h>
55 #include <visp3/core/vpXmlParserCamera.h>
56 #include <visp3/detection/vpDetectorAprilTag.h>
57 #include <visp3/gui/vpDisplayGDI.h>
58 #include <visp3/gui/vpDisplayX.h>
59 #include <visp3/gui/vpPlot.h>
60 #include <visp3/robot/vpRobotMavsdk.h>
61 #include <visp3/sensor/vpRealSense2.h>
62 #include <visp3/visual_features/vpFeatureBuilder.h>
63 #include <visp3/visual_features/vpFeatureMomentAreaNormalized.h>
64 #include <visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h>
65 #include <visp3/visual_features/vpFeatureVanishingPoint.h>
66 #include <visp3/vs/vpServo.h>
67 #include <visp3/vs/vpServoDisplay.h>
68 
69 // Comment next line to disable sending commands to the robot
70 #define CONTROL_UAV
71 
72 bool compareImagePoint(std::pair<size_t, vpImagePoint> p1, std::pair<size_t, vpImagePoint> p2)
73 {
74  return (p1.second.get_v() < p2.second.get_v());
75 };
76 
93 int main(int argc, char **argv)
94 {
95  try {
96  std::string opt_connecting_info = "udp://:192.168.30.111:14552";
97  double tagSize = -1;
98  double opt_distance_to_tag = -1;
99  bool opt_has_distance_to_tag = false;
100  int opt_display_fps = 10;
101  bool opt_verbose = false;
102 
103  int acq_fps = 30;
104 
105  if (argc >= 3 && std::string(argv[1]) == "--tag-size") {
106  tagSize = std::atof(argv[2]); // Tag size option is required
107  if (tagSize <= 0) {
108  std::cout << "Error : invalid tag size." << std::endl << "See " << argv[0] << " --help" << std::endl;
109  return EXIT_FAILURE;
110  }
111  for (int i = 3; i < argc; i++) {
112  if (std::string(argv[i]) == "--co" && i + 1 < argc) {
113  opt_connecting_info = std::string(argv[i + 1]);
114  i++;
115  }
116  else if (std::string(argv[i]) == "--distance-to-tag" && i + 1 < argc) {
117  opt_distance_to_tag = std::atof(argv[i + 1]);
118  if (opt_distance_to_tag <= 0) {
119  std::cout << "Error : invalid distance to tag." << std::endl << "See " << argv[0] << " --help" << std::endl;
120  return EXIT_FAILURE;
121  }
122  opt_has_distance_to_tag = true;
123  i++;
124 
125  }
126  else if (std::string(argv[i]) == "--display-fps" && i + 1 < argc) {
127  opt_display_fps = std::stoi(std::string(argv[i + 1]));
128  i++;
129  }
130  else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
131  opt_verbose = true;
132  }
133  else {
134  std::cout << "Error : unknown parameter " << argv[i] << std::endl
135  << "See " << argv[0] << " --help" << std::endl;
136  return EXIT_FAILURE;
137  }
138  }
139  }
140  else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) {
141  std::cout << "\nUsage:\n"
142  << " " << argv[0]
143  << " [--tag-size <tag size [m]>] [--co <connection information>] [--distance-to-tag <distance>]"
144  << " [--display-fps <display fps>] [--verbose] [-v] [--help] [-h]\n"
145  << std::endl
146  << "Description:\n"
147  << " --tag-size <size>\n"
148  << " The size of the tag to detect in meters, required.\n\n"
149  << " --co <connection information>\n"
150  << " - UDP: udp://[host][:port]\n"
151  << " - TCP: tcp://[host][:port]\n"
152  << " - serial: serial://[path][:baudrate]\n"
153  << " - Default: udp://192.168.30.111:14552).\n\n"
154  << " --distance-to-tag <distance>\n"
155  << " The desired distance to the tag in meters (default: 1 meter).\n\n"
156  << " --display-fps <display_fps>\n"
157  << " The desired fps rate for the video display (default: 10 fps).\n\n"
158  << " --verbose, -v\n"
159  << " Enables verbosity (drone information messages and velocity commands\n"
160  << " are then displayed).\n\n"
161  << " --help, -h\n"
162  << " Print help message.\n"
163  << std::endl;
164  return EXIT_SUCCESS;
165 
166  }
167  else {
168  std::cout << "Error : tag size parameter required." << std::endl << "See " << argv[0] << " --help" << std::endl;
169  return EXIT_FAILURE;
170  }
171 
172  std::cout << std::endl
173  << "WARNING:" << std::endl
174  << " - This program does no sensing or avoiding of obstacles, " << std::endl
175  << " the drone WILL collide with any objects in the way! Make sure the " << std::endl
176  << " drone has approximately 3 meters of free space on all sides." << std::endl
177  << " - The drone uses a forward-facing camera for Apriltag detection," << std::endl
178  << " make sure the drone flies above a non-uniform flooring," << std::endl
179  << " or its movement will be inacurate and dangerous !" << std::endl
180  << std::endl;
181 
182 // Connect to the drone
183  vpRobotMavsdk drone(opt_connecting_info);
184 
185  if (drone.isRunning()) {
186  vpRealSense2 rs;
187 
188  std::string product_line = rs.getProductLine();
189  if (opt_verbose) {
190  std::cout << "Product line: " << product_line << std::endl;
191  }
192 
193  if (product_line == "T200") {
194  std::cout << "This example doesn't support T200 product line family !" << std::endl;
195  return EXIT_SUCCESS;
196  }
197  rs2::config config;
198 
199  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, acq_fps);
200  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, acq_fps);
201  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, acq_fps);
202 
203  rs.open(config);
204  vpCameraParameters cam = rs.getCameraParameters(RS2_STREAM_COLOR);
205 
206  if (opt_verbose) {
207  cam.printParameters();
208  }
209 
210 #ifdef CONTROL_UAV
211  drone.doFlatTrim(); // Flat trim calibration
212  drone.takeOff(); // Take off
213 #endif
214 
215  vpImage<unsigned char> I(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
216 
217 #if defined(VISP_HAVE_X11)
219 #elif defined(VISP_HAVE_GTK)
221 #elif defined(VISP_HAVE_GDI)
223 #elif defined(HAVE_OPENCV_HIGHGUI)
225 #endif
226  int orig_displayX = 100;
227  int orig_displayY = 100;
228  display.init(I, orig_displayX, orig_displayY, "DRONE VIEW");
230  vpDisplay::flush(I);
231  double time_since_last_display = vpTime::measureTimeMs();
232 
233  vpPlot plotter(1, 700, 700, orig_displayX + static_cast<int>(I.getWidth()) + 20, orig_displayY,
234  "Visual servoing tasks");
235  unsigned int iter = 0;
236 
239  vpDetectorAprilTag detector(tagFamily); // The detector used to detect Apritags
241  detector.setAprilTagQuadDecimate(4.0);
242  detector.setAprilTagNbThreads(4);
243  detector.setDisplayTag(true);
244 
245  vpServo task; // Visual servoing task
246 
247  // double lambda = 0.5;
248  vpAdaptiveGain lambda = vpAdaptiveGain(1.5, 0.7, 30);
251  task.setLambda(lambda);
252 
254  /*
255  * In the following section, (c1) is an intermediate frame attached to the camera
256  * that has axis aligned with the FLU body frame. The real camera frame is denoted (c).
257  * The FLU body-frame of the drone denoted (e) is the one in which we need to convert
258  * every velocity command computed by visual servoing.
259  *
260  * We can easily estimate the homogeneous matrix between (c1) and (c) where
261  * in our case we have -10 degrees around X camera axis.
262  * Then for the transformation between (e) and (c1) frames we can consider only translations.
263  *
264  * Using those matrices, we can in the end obtain the homogeneous matrix between (c) and (e) frames.
265  * This homogeneous matrix is then used to compute the velocity twist matrix cVe.
266  */
267  vpRxyzVector c1_rxyz_c(vpMath::rad(-10.0), vpMath::rad(0), 0);
268  vpRotationMatrix c1Rc(c1_rxyz_c); // Rotation between (c1) and (c)
269  vpHomogeneousMatrix c1Mc(vpTranslationVector(), c1Rc); // Homogeneous matrix between (c1) and (c)
270 
271  vpRotationMatrix c1Re { 1, 0, 0, 0, 0, 1, 0, -1, 0 }; // Rotation between (c1) and (e)
272  vpTranslationVector c1te(0, -0.03, -0.07); // Translation between (c1) and (e)
273  vpHomogeneousMatrix c1Me(c1te, c1Re); // Homogeneous matrix between (c1) and (e)
274 
275  vpHomogeneousMatrix cMe = c1Mc.inverse() * c1Me; // Homogeneous matrix between (c) and (e)
276 
277  vpVelocityTwistMatrix cVe(cMe);
279  task.set_cVe(cVe);
280 
281  vpMatrix eJe(6, 4, 0);
282 
283  eJe[0][0] = 1;
284  eJe[1][1] = 1;
285  eJe[2][2] = 1;
286  eJe[5][3] = 1;
287 
288  // double Z_d = 1.; // Desired distance to the target
289  double Z_d = (opt_has_distance_to_tag ? opt_distance_to_tag : 1.);
290 
291  // Define the desired polygon corresponding the the AprilTag CLOCKWISE
292  double X[4] = { tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2. };
293  double Y[4] = { tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2. };
294  std::vector<vpPoint> vec_P, vec_P_d;
295 
296  for (int i = 0; i < 4; i++) {
297  vpPoint P_d(X[i], Y[i], 0);
298  vpHomogeneousMatrix cdMo(0, 0, Z_d, 0, 0, 0);
299  P_d.track(cdMo); //
300  vec_P_d.push_back(P_d);
301  }
302  vpMomentObject m_obj(3), m_obj_d(3);
303  vpMomentDatabase mdb, mdb_d;
304  vpMomentBasic mb_d; // Here only to get the desired area m00
305  vpMomentGravityCenter mg, mg_d;
306  vpMomentCentered mc, mc_d;
307  vpMomentAreaNormalized man(0, Z_d), man_d(0, Z_d); // Declare normalized area updated below with m00
308  vpMomentGravityCenterNormalized mgn, mgn_d; // Declare normalized gravity center
309 
310  // Desired moments
311  m_obj_d.setType(vpMomentObject::DENSE_POLYGON); // Consider the AprilTag as a polygon
312  m_obj_d.fromVector(vec_P_d); // Initialize the object with the points coordinates
313 
314  mb_d.linkTo(mdb_d); // Add basic moments to database
315  mg_d.linkTo(mdb_d); // Add gravity center to database
316  mc_d.linkTo(mdb_d); // Add centered moments to database
317  man_d.linkTo(mdb_d); // Add area normalized to database
318  mgn_d.linkTo(mdb_d); // Add gravity center normalized to database
319  mdb_d.updateAll(m_obj_d); // All of the moments must be updated, not just an_d
320  mg_d.compute(); // Compute gravity center moment
321  mc_d.compute(); // Compute centered moments AFTER gravity center
322 
323  double area = 0;
324  if (m_obj_d.getType() == vpMomentObject::DISCRETE)
325  area = mb_d.get(2, 0) + mb_d.get(0, 2);
326  else
327  area = mb_d.get(0, 0);
328  // Update moment with the desired area
329  man_d.setDesiredArea(area);
330 
331  man_d.compute(); // Compute area normalized moment AFTER centered moments
332  mgn_d.compute(); // Compute gravity center normalized moment AFTER area normalized
333  // moment
334 
335  // Desired plane
336  double A = 0.0;
337  double B = 0.0;
338  double C = 1.0 / Z_d;
339 
340  // Construct area normalized features
341  vpFeatureMomentGravityCenterNormalized s_mgn(mdb, A, B, C), s_mgn_d(mdb_d, A, B, C);
342  vpFeatureMomentAreaNormalized s_man(mdb, A, B, C), s_man_d(mdb_d, A, B, C);
343  vpFeatureVanishingPoint s_vp, s_vp_d;
344 
345  // Add the features
346  task.addFeature(s_mgn, s_mgn_d);
347  task.addFeature(s_man, s_man_d);
349 
350  plotter.initGraph(0, 4);
351  plotter.setLegend(0, 0, "Xn"); // Distance from center on X axis feature
352  plotter.setLegend(0, 1, "Yn"); // Distance from center on Y axis feature
353  plotter.setLegend(0, 2, "an"); // Tag area feature
354  plotter.setLegend(0, 3, "atan(1/rho)"); // Vanishing point feature
355 
356  // Update desired gravity center normalized feature
357  s_mgn_d.update(A, B, C);
358  s_mgn_d.compute_interaction();
359  // Update desired area normalized feature
360  s_man_d.update(A, B, C);
361  s_man_d.compute_interaction();
362 
363  // Update desired vanishing point feature for the horizontal line
364  s_vp_d.setAtanOneOverRho(0);
365  s_vp_d.setAlpha(0);
366 
367  bool condition;
368  bool runLoop = true;
369  bool vec_ip_has_been_sorted = false;
370  bool send_velocities = false;
371  std::vector<std::pair<size_t, vpImagePoint> > vec_ip_sorted;
372 
373  //** Visual servoing loop **//
374  while (drone.isRunning() && runLoop) {
375 
376  double startTime = vpTime::measureTimeMs();
377 
378  // drone.getGrayscaleImage(I);
379  rs.acquire(I);
380 
381  condition = (startTime - time_since_last_display) > 1000. / opt_display_fps ? true : false;
382  if (condition) {
384  time_since_last_display = vpTime::measureTimeMs();
385  }
386 
387  std::vector<vpHomogeneousMatrix> cMo_vec;
388  detector.detect(I, tagSize, cam, cMo_vec); // Detect AprilTags in current image
389  double t = vpTime::measureTimeMs() - startTime;
390 
391  if (condition) {
392  std::stringstream ss;
393  ss << "Detection time: " << t << " ms";
394  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
395  }
396 
397  if (detector.getNbObjects() != 0) {
398 
399  // Update current points used to compute the moments
400  std::vector<vpImagePoint> vec_ip = detector.getPolygon(0);
401  vec_P.clear();
402  for (size_t i = 0; i < vec_ip.size(); i++) { // size = 4
403  double x = 0, y = 0;
404  vpPixelMeterConversion::convertPoint(cam, vec_ip[i], x, y);
405  vpPoint P;
406  P.set_x(x);
407  P.set_y(y);
408  vec_P.push_back(P);
409  }
410 
411  // Current moments
412  m_obj.setType(vpMomentObject::DENSE_POLYGON); // Consider the AprilTag as a polygon
413  m_obj.fromVector(vec_P); // Initialize the object with the points coordinates
414 
415  mg.linkTo(mdb); // Add gravity center to database
416  mc.linkTo(mdb); // Add centered moments to database
417  man.linkTo(mdb); // Add area normalized to database
418  mgn.linkTo(mdb); // Add gravity center normalized to database
419  mdb.updateAll(m_obj); // All of the moments must be updated, not just an_d
420  mg.compute(); // Compute gravity center moment
421  mc.compute(); // Compute centered moments AFTER gravity center
422  man.setDesiredArea(area); // Desired area was init at 0 (unknow at construction),
423  // need to be updated here
424  man.compute(); // Compute area normalized moment AFTER centered moment
425  mgn.compute(); // Compute gravity center normalized moment AFTER area normalized
426  // moment
427 
428  s_mgn.update(A, B, C);
429  s_mgn.compute_interaction();
430  s_man.update(A, B, C);
431  s_man.compute_interaction();
432 
433  /* Sort points from their height in the image, and keep original indexes.
434  This is done once, in order to be independent from the orientation of the tag
435  when detecting vanishing points. */
436  if (!vec_ip_has_been_sorted) {
437  for (size_t i = 0; i < vec_ip.size(); i++) {
438 
439  // Add the points and their corresponding index
440  std::pair<size_t, vpImagePoint> index_pair = std::pair<size_t, vpImagePoint>(i, vec_ip[i]);
441  vec_ip_sorted.push_back(index_pair);
442  }
443 
444  // Sort the points and indexes from the v value of the points
445  std::sort(vec_ip_sorted.begin(), vec_ip_sorted.end(), compareImagePoint);
446 
447  vec_ip_has_been_sorted = true;
448  }
449 
450  // Use the two highest points for the first line, and the two others for the second
451  // line.
452  vpFeatureBuilder::create(s_vp, cam, vec_ip[vec_ip_sorted[0].first], vec_ip[vec_ip_sorted[1].first],
453  vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first],
455 
456  task.set_cVe(cVe);
457  task.set_eJe(eJe);
458 
459  // Compute the control law. Velocities are computed in the mobile robot reference
460  // frame
461  vpColVector ve = task.computeControlLaw();
462  if (!send_velocities) {
463  ve = 0;
464  }
465 
466  // Sending the control law to the drone
467  if (opt_verbose) {
468  std::cout << "ve: " << ve.t() << std::endl;
469  }
470 
471 #ifdef CONTROL_UAV
472  drone.setVelocity(ve);
473 #endif
474 
475  if (condition) {
476  for (size_t i = 0; i < 4; i++) {
477  vpDisplay::displayCross(I, vec_ip[i], 15, vpColor::red, 1);
478  std::stringstream ss;
479  ss << i;
480  vpDisplay::displayText(I, vec_ip[i] + vpImagePoint(15, 15), ss.str(), vpColor::green);
481  }
482 
483  // Display visual features
485  3); // Current polygon used to compure an moment
486  vpDisplay::displayCross(I, detector.getCog(0), 15, vpColor::green,
487  3); // Current polygon used to compute a moment
488  vpDisplay::displayLine(I, 0, static_cast<int>(cam.get_u0()), static_cast<int>(I.getHeight()) - 1,
489  static_cast<int>(cam.get_u0()), vpColor::red,
490  3); // Vertical line as desired x position
491  vpDisplay::displayLine(I, static_cast<int>(cam.get_v0()), 0, static_cast<int>(cam.get_v0()),
492  static_cast<int>(I.getWidth()) - 1, vpColor::red,
493  3); // Horizontal line as desired y position
494 
495  // Display lines corresponding to the vanishing point for the horizontal lines
496  vpDisplay::displayLine(I, vec_ip[vec_ip_sorted[0].first], vec_ip[vec_ip_sorted[1].first], vpColor::red, 1,
497  false);
498  vpDisplay::displayLine(I, vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first], vpColor::red, 1,
499  false);
500  }
501 
502  }
503  else {
504 
505  std::stringstream sserr;
506  sserr << "Failed to detect an Apriltag, or detected multiple ones";
507  if (condition) {
508  vpDisplay::displayText(I, 120, 20, sserr.str(), vpColor::red);
509  vpDisplay::flush(I);
510  }
511  else {
512  std::cout << sserr.str() << std::endl;
513  }
514 #ifdef CONTROL_UAV
515  drone.stopMoving(); // In this case, we stop the drone
516 #endif
517  }
518 
519  if (condition) {
520  {
521  std::stringstream ss;
522  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot")
523  << ", right click to quit.";
524  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
525  }
526  vpDisplay::flush(I);
527 
528  plotter.plot(0, iter, task.getError());
529  }
530 
532  if (vpDisplay::getClick(I, button, false)) {
533  switch (button) {
535  send_velocities = !send_velocities;
536  break;
537 
539  drone.land();
540  runLoop = false;
541  break;
542 
543  default:
544  break;
545  }
546  }
547 
548  double totalTime = vpTime::measureTimeMs() - startTime;
549  std::stringstream sstime;
550  sstime << "Total time: " << totalTime << " ms";
551  if (condition) {
552  vpDisplay::displayText(I, 80, 20, sstime.str(), vpColor::red);
553  vpDisplay::flush(I);
554  }
555 
556  iter++;
557  vpTime::wait(startTime, 1000. / acq_fps);
558  }
559 
560  return EXIT_SUCCESS;
561  }
562  else {
563  std::cout << "ERROR : failed to setup drone control." << std::endl;
564  return EXIT_FAILURE;
565  }
566  }
567  catch (const vpException &e) {
568  std::cout << "Caught an exception: " << e << std::endl;
569  return EXIT_FAILURE;
570  }
571 }
572 
573 #else
574 
575 int main()
576 {
577 #ifndef VISP_HAVE_MAVSDK
578  std::cout << "\nThis example requires mavsdk library. You should install it, configure and rebuid ViSP.\n" << std::endl;
579 #endif
580 #ifndef VISP_HAVE_REALSENSE2
581  std::cout << "\nThis example requires librealsense2 library. You should install it, configure and rebuid ViSP.\n" << std::endl;
582 #endif
583 #if !defined(VISP_HAVE_PUGIXML)
584  std::cout << "\nThis example requires pugixml built-in 3rdparty." << std::endl;
585 #endif
586 #if !((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
587  std::cout
588  << "\nThis example requires at least cxx17. You should enable cxx17 during ViSP configuration with cmake and "
589  "rebuild ViSP.\n"
590  << std::endl;
591 #endif
592  return EXIT_SUCCESS;
593 }
594 
595 #endif // #if defined(VISP_HAVE_MAVSDK)
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
vpRowVector t() const
static const vpColor red
Definition: vpColor.h:211
static const vpColor green
Definition: vpColor.h:214
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.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
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
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)
static void displayPolygon(const vpImage< unsigned char > &I, const std::vector< vpImagePoint > &vip, const vpColor &color, unsigned int thickness=1, bool closed=true)
error that can be emitted by ViSP classes.
Definition: vpException.h:59
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Functionality computation for normalized surface moment feature. Computes the interaction matrix asso...
Functionality computation for centered and normalized moment feature. Computes the interaction matrix...
static unsigned int selectAtanOneOverRho()
void setAlpha(double alpha)
Set vanishing point feature value.
void setAtanOneOverRho(double atan_one_over_rho)
Set vanishing point feature value.
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
unsigned int getWidth() const
Definition: vpImage.h:245
unsigned int getHeight() const
Definition: vpImage.h:184
static double rad(double deg)
Definition: vpMath.h:127
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:146
Class handling the normalized surface moment that is invariant in scale and used to estimate depth.
This class defines the 2D basic moment . This class is a wrapper for vpMomentObject wich allows to us...
Definition: vpMomentBasic.h:70
const std::vector< double > & get() const
This class defines the double-indexed centered moment descriptor .
This class allows to register all vpMoments so they can access each other according to their dependen...
virtual void updateAll(vpMomentObject &object)
Class describing 2D normalized gravity center moment.
Class describing 2D gravity center moment.
Class for generic objects.
void linkTo(vpMomentDatabase &moments)
Definition: vpMoment.cpp:95
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:109
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:77
void set_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:504
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:506
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())
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const
std::string getProductLine()
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:176
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:378
@ EYEINHAND_L_cVe_eJe
Definition: vpServo.h:162
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:329
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition: vpServo.h:1028
void setLambda(double c)
Definition: vpServo.h:976
void set_eJe(const vpMatrix &eJe_)
Definition: vpServo.h:1091
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:132
vpColVector getError() const
Definition: vpServo.h:504
vpColVector computeControlLaw()
Definition: vpServo.cpp:703
@ CURRENT
Definition: vpServo.h:196
Class that consider the case of a translation vector.
void display(vpImage< unsigned char > &I, const std::string &title)
Display a gray-scale image.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double measureTimeMs()