Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
servoBebop2.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 Parrot Bebop 2 drone in ViSP.
33  *
34  * Authors:
35  * Gatien Gaumerais
36  *
37 *****************************************************************************/
38 
39 #include <iostream>
40 
41 #include <visp3/core/vpConfig.h>
42 #include <visp3/core/vpMomentAreaNormalized.h>
43 #include <visp3/core/vpMomentBasic.h>
44 #include <visp3/core/vpMomentCentered.h>
45 #include <visp3/core/vpMomentDatabase.h>
46 #include <visp3/core/vpMomentGravityCenter.h>
47 #include <visp3/core/vpMomentGravityCenterNormalized.h>
48 #include <visp3/core/vpMomentObject.h>
49 #include <visp3/core/vpPixelMeterConversion.h>
50 #include <visp3/core/vpPoint.h>
51 #include <visp3/core/vpTime.h>
52 #include <visp3/core/vpXmlParserCamera.h>
53 #include <visp3/detection/vpDetectorAprilTag.h>
54 #include <visp3/gui/vpDisplayX.h>
55 #include <visp3/gui/vpPlot.h>
56 #include <visp3/robot/vpRobotBebop2.h>
57 #include <visp3/visual_features/vpFeatureBuilder.h>
58 #include <visp3/visual_features/vpFeatureMomentAreaNormalized.h>
59 #include <visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h>
60 #include <visp3/visual_features/vpFeatureVanishingPoint.h>
61 #include <visp3/vs/vpServo.h>
62 #include <visp3/vs/vpServoDisplay.h>
63 
64 #if !defined(VISP_HAVE_ARSDK)
65 int main()
66 {
67  std::cout << "\nThis example requires Parrot ARSDK3 library. You should install it.\n" << std::endl;
68  return EXIT_SUCCESS;
69 }
70 #elif !defined(VISP_HAVE_FFMPEG)
71 int main()
72 {
73  std::cout << "\nThis example requires ffmpeg library. You should install it.\n" << std::endl;
74  return EXIT_SUCCESS;
75 }
76 #elif !defined(VISP_HAVE_PUGIXML)
77 int main()
78 {
79  std::cout << "\nThis example requires pugixml built-in 3rdparty library. You should enable it.\n" << std::endl;
80  return EXIT_SUCCESS;
81 }
82 
83 #else
84 
85 #ifdef ENABLE_VISP_NAMESPACE
86 using namespace VISP_NAMESPACE_NAME;
87 #endif
88 
89 bool compareImagePoint(std::pair<size_t, vpImagePoint> p1, std::pair<size_t, vpImagePoint> p2)
90 {
91  return (p1.second.get_v() < p2.second.get_v());
92 };
93 
105 int main(int argc, char **argv)
106 {
107  try {
108 
109  std::string ip_address = "192.168.42.1";
110  std::string opt_cam_parameters;
111  bool opt_has_cam_parameters = false;
112 
113  double tagSize = -1;
114 
115  double opt_distance_to_tag = -1;
116  bool opt_has_distance_to_tag = false;
117 
118  int stream_res = 0; // Default 480p resolution
119 
120  bool verbose = false;
121 
122  if (argc >= 3 && std::string(argv[1]) == "--tag_size") {
123  tagSize = std::atof(argv[2]); // Tag size option is required
124  if (tagSize <= 0) {
125  std::cout << "Error : invalid tag size." << std::endl << "See " << argv[0] << " --help" << std::endl;
126  return EXIT_FAILURE;
127  }
128  for (int i = 3; i < argc; i++) {
129  if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
130  ip_address = std::string(argv[i + 1]);
131  i++;
132  }
133  else if (std::string(argv[i]) == "--distance_to_tag" && i + 1 < argc) {
134  opt_distance_to_tag = std::atof(argv[i + 1]);
135  if (opt_distance_to_tag <= 0) {
136  std::cout << "Error : invalid distance to tag." << std::endl << "See " << argv[0] << " --help" << std::endl;
137  return EXIT_FAILURE;
138  }
139  opt_has_distance_to_tag = true;
140  i++;
141  }
142  else if (std::string(argv[i]) == "--intrinsic") {
143 
144  opt_cam_parameters = std::string(argv[i + 1]);
145  opt_has_cam_parameters = true;
146  i++;
147  }
148  else if (std::string(argv[i]) == "--hd_stream") {
149  stream_res = 1;
150  }
151  else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
152  verbose = true;
153  }
154  else {
155  std::cout << "Error : unknown parameter " << argv[i] << std::endl
156  << "See " << argv[0] << " --help" << std::endl;
157  return EXIT_FAILURE;
158  }
159  }
160  }
161  else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) {
162  std::cout << "\nUsage:\n"
163  << " " << argv[0]
164  << " [--tag_size <size>] [--ip <drone ip>] [--distance_to_tag <distance>] [--intrinsic <xml file>] "
165  << "[--hd_stream] [--verbose] [-v] [--help] [-h]\n"
166  << std::endl
167  << "Description:\n"
168  << " --tag_size <size>\n"
169  << " The size of the tag to detect in meters, required.\n\n"
170  << " --ip <drone ip>\n"
171  << " Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n"
172  << " --distance_to_tag <distance>\n"
173  << " The desired distance to the tag in meters (default: 1 meter).\n\n"
174  << " --intrinsic <xml file>\n"
175  << " XML file containing computed intrinsic camera parameters (default: empty).\n\n"
176  << " --hd_stream\n"
177  << " Enables HD 720p streaming instead of default 480p.\n"
178  << " Allows to increase range and accuracy of the tag detection,\n"
179  << " but increases latency and computation time.\n"
180  << " Caution: camera calibration settings are different for the two resolutions.\n"
181  << " Make sure that if you pass custom intrinsic camera parameters,\n"
182  << " they were obtained with the correct resolution.\n\n"
183  << " --verbose, -v\n"
184  << " Enables verbose (drone information messages and velocity commands\n"
185  << " are then displayed).\n\n"
186  << " --help, -h\n"
187  << " Print help message.\n"
188  << std::endl;
189  return EXIT_SUCCESS;
190  }
191  else {
192  std::cout << "Error : tag size parameter required." << std::endl << "See " << argv[0] << " --help" << std::endl;
193  return EXIT_FAILURE;
194  }
195 
196  std::cout
197  << "\nWARNING: \n - This program does no sensing or avoiding of "
198  "obstacles, \n"
199  "the drone WILL collide with any objects in the way! Make sure "
200  "the \n"
201  "drone has approximately 3 meters of free space on all sides.\n"
202  " - The drone uses a downward-facing camera for horizontal speed estimation,\n make sure the drone flies "
203  "above a non-uniform flooring,\n or its movement will be inacurate and dangerous !\n"
204 
205  << std::endl;
206 
207  vpRobotBebop2 drone(
208  verbose, true, ip_address); // Create the drone with desired verbose level, settings reset, and corresponding IP
209 
210  if (drone.isRunning()) {
211 
212  drone.setVideoResolution(stream_res); // Set video resolution to 480p (default) or 720p
213 
214  drone.setStreamingMode(0); // Set lowest latency stream mode
215  drone.setVideoStabilisationMode(0); // Disable video stabilisation
216 
217  drone.doFlatTrim(); // Flat trim calibration
218 
219  drone.startStreaming(); // Start streaming and decoding video data
220 
221  drone.setExposure(1.5f); // Set exposure to max so that the aprilTag detection is more efficient
222 
223  drone.setCameraOrientation(-5., 0.,
224  true); // Set camera to look slightly down so that the drone is slightly above the tag
225 
226  drone.takeOff(true); // Take off
227 
229  drone.getGrayscaleImage(I);
230 
231 #if defined(VISP_HAVE_X11)
232  vpDisplayX display;
233 #elif defined(VISP_HAVE_GTK)
234  vpDisplayGTK display;
235 #elif defined(VISP_HAVE_GDI)
236  vpDisplayGDI display;
237 #elif defined(HAVE_OPENCV_HIGHGUI)
238  vpDisplayOpenCV display;
239 #endif
240  int orig_displayX = 100;
241  int orig_displayY = 100;
242  display.init(I, orig_displayX, orig_displayY, "DRONE VIEW");
244  vpDisplay::flush(I);
245 
246  vpPlot plotter(1, 700, 700, orig_displayX + static_cast<int>(I.getWidth()) + 20, orig_displayY,
247  "Visual servoing tasks");
248  unsigned int iter = 0;
249 
251  vpDetectorAprilTag detector(tagFamily); // The detector used to detect Apritags
252  detector.setAprilTagQuadDecimate(4.0);
253  detector.setAprilTagNbThreads(4);
254  detector.setDisplayTag(true);
255 
256  vpCameraParameters cam;
257 
258  if (opt_has_cam_parameters) {
259 
262 
263  if (p.parse(cam, opt_cam_parameters, "Camera", projModel, I.getWidth(), I.getHeight()) !=
265  std::cout << "Cannot find parameters in XML file " << opt_cam_parameters << std::endl;
266  if (drone.getVideoHeight() == 720) { // 720p streaming
267  cam.initPersProjWithoutDistortion(785.6412585, 785.3322447, 637.9049857, 359.7524531);
268  }
269  else { // 480p streaming
270  cam.initPersProjWithoutDistortion(531.9213063, 520.8495788, 429.133986, 240.9464457);
271  }
272  }
273  }
274  else {
275  std::cout << "Setting default camera parameters ... " << std::endl;
276  if (drone.getVideoHeight() == 720) { // 720p streaming
277  cam.initPersProjWithoutDistortion(785.6412585, 785.3322447, 637.9049857, 359.7524531);
278  }
279  else { // 480p streaming
280  cam.initPersProjWithoutDistortion(531.9213063, 520.8495788, 429.133986, 240.9464457);
281  }
282  }
283  cam.printParameters();
284 
285  vpServo task; // Visual servoing task
286 
287  // double lambda = 0.5;
288  vpAdaptiveGain lambda = vpAdaptiveGain(1.5, 0.7, 30);
291  task.setLambda(lambda);
292 
293  /*
294  In the following section, camera 1 refers to camera coordonates system of the drone, but without taking camera
295  pan and camera tilt into account.
296  Those values are taken into consideration in Camera 2.
297  E is the effective coordinate system of the drone, the one in which we need to convert every velocity command.
298 
299  We can easily compute homogeneous matrix between camera 1 and camera 2, and between camera 1
300  and effective coordonate system E of the drone.
301 
302  Using those matrices, we can in the end obtain the matrix between c2 and E
303  */
304  vpRxyzVector c1_rxyz_c2(vpMath::rad(drone.getCurrentCameraTilt()), vpMath::rad(drone.getCurrentCameraPan()), 0);
305  vpRotationMatrix c1Rc2(c1_rxyz_c2); // Rotation between camera 1 and 2
306  vpHomogeneousMatrix c1Mc2(vpTranslationVector(), c1Rc2); // Homogeneous matrix between c1 and c2
307 
308  vpRotationMatrix c1Re { 0, 1, 0, 0, 0, 1, 1, 0, 0 }; // Rotation between camera 1 and E
309  vpTranslationVector c1te(0, 0, -0.09); // Translation between camera 1 and E
310  vpHomogeneousMatrix c1Me(c1te, c1Re); // Homogeneous matrix between c1 and E
311 
312  vpHomogeneousMatrix c2Me = c1Mc2.inverse() * c1Me; // Homogeneous matrix between c2 and E
313 
314  vpVelocityTwistMatrix cVe(c2Me);
315  task.set_cVe(cVe);
316 
317  vpMatrix eJe(6, 4, 0);
318 
319  eJe[0][0] = 1;
320  eJe[1][1] = 1;
321  eJe[2][2] = 1;
322  eJe[5][3] = 1;
323 
324  // double Z_d = 1.; // Desired distance to the target
325  double Z_d = (opt_has_distance_to_tag ? opt_distance_to_tag : 1.);
326 
327  // Define the desired polygon corresponding the the AprilTag CLOCKWISE
328  double X[4] = { tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2. };
329  double Y[4] = { tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2. };
330  std::vector<vpPoint> vec_P, vec_P_d;
331 
332  for (int i = 0; i < 4; i++) {
333  vpPoint P_d(X[i], Y[i], 0);
334  vpHomogeneousMatrix cdMo(0, 0, Z_d, 0, 0, 0);
335  P_d.track(cdMo); //
336  vec_P_d.push_back(P_d);
337  }
338  vpMomentObject m_obj(3), m_obj_d(3);
339  vpMomentDatabase mdb, mdb_d;
340  vpMomentBasic mb_d; // Here only to get the desired area m00
341  vpMomentGravityCenter mg, mg_d;
342  vpMomentCentered mc, mc_d;
343  vpMomentAreaNormalized man(0, Z_d), man_d(0, Z_d); // Declare normalized area updated below with m00
344  vpMomentGravityCenterNormalized mgn, mgn_d; // Declare normalized gravity center
345 
346  // Desired moments
347  m_obj_d.setType(vpMomentObject::DENSE_POLYGON); // Consider the AprilTag as a polygon
348  m_obj_d.fromVector(vec_P_d); // Initialize the object with the points coordinates
349 
350  mb_d.linkTo(mdb_d); // Add basic moments to database
351  mg_d.linkTo(mdb_d); // Add gravity center to database
352  mc_d.linkTo(mdb_d); // Add centered moments to database
353  man_d.linkTo(mdb_d); // Add area normalized to database
354  mgn_d.linkTo(mdb_d); // Add gravity center normalized to database
355  mdb_d.updateAll(m_obj_d); // All of the moments must be updated, not just an_d
356  mg_d.compute(); // Compute gravity center moment
357  mc_d.compute(); // Compute centered moments AFTER gravity center
358 
359  double area = 0;
360  if (m_obj_d.getType() == vpMomentObject::DISCRETE)
361  area = mb_d.get(2, 0) + mb_d.get(0, 2);
362  else
363  area = mb_d.get(0, 0);
364  // Update moment with the desired area
365  man_d.setDesiredArea(area);
366 
367  man_d.compute(); // Compute area normalized moment AFTER centered moments
368  mgn_d.compute(); // Compute gravity center normalized moment AFTER area normalized moment
369 
370  // Desired plane
371  double A = 0.0;
372  double B = 0.0;
373  double C = 1.0 / Z_d;
374 
375  // Construct area normalized features
376  vpFeatureMomentGravityCenterNormalized s_mgn(mdb, A, B, C), s_mgn_d(mdb_d, A, B, C);
377  vpFeatureMomentAreaNormalized s_man(mdb, A, B, C), s_man_d(mdb_d, A, B, C);
378  vpFeatureVanishingPoint s_vp, s_vp_d;
379 
380  // Add the features
381  task.addFeature(s_mgn, s_mgn_d);
382  task.addFeature(s_man, s_man_d);
384 
385  plotter.initGraph(0, 4);
386  plotter.setLegend(0, 0, "Xn"); // Distance from center on X axis feature
387  plotter.setLegend(0, 1, "Yn"); // Distance from center on Y axis feature
388  plotter.setLegend(0, 2, "an"); // Tag area feature
389  plotter.setLegend(0, 3, "atan(1/rho)"); // Vanishing point feature
390 
391  // Update desired gravity center normalized feature
392  s_mgn_d.update(A, B, C);
393  s_mgn_d.compute_interaction();
394  // Update desired area normalized feature
395  s_man_d.update(A, B, C);
396  s_man_d.compute_interaction();
397 
398  // Update desired vanishing point feature for the horizontal line
399  s_vp_d.setAtanOneOverRho(0);
400  s_vp_d.setAlpha(0);
401 
402  bool runLoop = true;
403  bool vec_ip_has_been_sorted = false;
404  std::vector<std::pair<size_t, vpImagePoint> > vec_ip_sorted;
405 
406  //** Visual servoing loop **//
407  while (drone.isRunning() && drone.isStreaming() && runLoop) {
408 
409  double startTime = vpTime::measureTimeMs();
410 
411  drone.getGrayscaleImage(I);
413 
414  std::vector<vpHomogeneousMatrix> cMo_vec;
415  detector.detect(I, tagSize, cam, cMo_vec); // Detect AprilTags in current image
416  double t = vpTime::measureTimeMs() - startTime;
417 
418  {
419  std::stringstream ss;
420  ss << "Detection time: " << t << " ms";
421  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
422  }
423 
424  if (detector.getNbObjects() == 1) {
425 
426  // Update current points used to compute the moments
427  std::vector<vpImagePoint> vec_ip = detector.getPolygon(0);
428  vec_P.clear();
429  for (size_t i = 0; i < vec_ip.size(); i++) { // size = 4
430  double x = 0, y = 0;
431  vpPixelMeterConversion::convertPoint(cam, vec_ip[i], x, y);
432  vpPoint P;
433  P.set_x(x);
434  P.set_y(y);
435  vec_P.push_back(P);
436  }
437 
438  // Current moments
439  m_obj.setType(vpMomentObject::DENSE_POLYGON); // Consider the AprilTag as a polygon
440  m_obj.fromVector(vec_P); // Initialize the object with the points coordinates
441 
442  mg.linkTo(mdb); // Add gravity center to database
443  mc.linkTo(mdb); // Add centered moments to database
444  man.linkTo(mdb); // Add area normalized to database
445  mgn.linkTo(mdb); // Add gravity center normalized to database
446  mdb.updateAll(m_obj); // All of the moments must be updated, not just an_d
447  mg.compute(); // Compute gravity center moment
448  mc.compute(); // Compute centered moments AFTER gravity center
449  man.setDesiredArea(area); // Desired area was init at 0 (unknow at construction), need to be updated here
450  man.compute(); // Compute area normalized moment AFTER centered moment
451  mgn.compute(); // Compute gravity center normalized moment AFTER area normalized moment
452 
453  s_mgn.update(A, B, C);
454  s_mgn.compute_interaction();
455  s_man.update(A, B, C);
456  s_man.compute_interaction();
457 
458  /* Sort points from their height in the image, and keep original indexes.
459  This is done once, in order to be independent from the orientation of the tag
460  when detecting vanishing points. */
461  if (!vec_ip_has_been_sorted) {
462  for (size_t i = 0; i < vec_ip.size(); i++) {
463 
464  // Add the points and their corresponding index
465  std::pair<size_t, vpImagePoint> index_pair = std::pair<size_t, vpImagePoint>(i, vec_ip[i]);
466  vec_ip_sorted.push_back(index_pair);
467  }
468 
469  // Sort the points and indexes from the v value of the points
470  std::sort(vec_ip_sorted.begin(), vec_ip_sorted.end(), compareImagePoint);
471 
472  vec_ip_has_been_sorted = true;
473  }
474 
475  // Use the two highest points for the first line, and the two others for the second line.
476  vpFeatureBuilder::create(s_vp, cam, vec_ip[vec_ip_sorted[0].first], vec_ip[vec_ip_sorted[1].first],
477  vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first],
479 
480  task.set_cVe(cVe);
481  task.set_eJe(eJe);
482 
483  // Compute the control law. Velocities are computed in the mobile robot reference frame
484  vpColVector ve = task.computeControlLaw();
485 
486  // Sending the control law to the drone
487  if (verbose) {
488  std::cout << "ve: " << ve.t() << std::endl;
489  }
490  drone.setVelocity(ve, 1.0);
491 
492  for (size_t i = 0; i < 4; i++) {
493  vpDisplay::displayCross(I, vec_ip[i], 15, vpColor::red, 1);
494  std::stringstream ss;
495  ss << i;
496  vpDisplay::displayText(I, vec_ip[i] + vpImagePoint(15, 15), ss.str(), vpColor::green);
497  }
498 
499  // Display visual features
500  vpDisplay::displayPolygon(I, vec_ip, vpColor::green, 3); // Current polygon used to compure an moment
501  vpDisplay::displayCross(I, detector.getCog(0), 15, vpColor::green,
502  3); // Current polygon used to compute a moment
503  vpDisplay::displayLine(I, 0, static_cast<int>(cam.get_u0()), static_cast<int>(I.getHeight()) - 1,
504  static_cast<int>(cam.get_u0()), vpColor::red,
505  3); // Vertical line as desired x position
506  vpDisplay::displayLine(I, static_cast<int>(cam.get_v0()), 0, static_cast<int>(cam.get_v0()),
507  static_cast<int>(I.getWidth()) - 1, vpColor::red,
508  3); // Horizontal line as desired y position
509 
510  // Display lines corresponding to the vanishing point for the horizontal lines
511  vpDisplay::displayLine(I, vec_ip[vec_ip_sorted[0].first], vec_ip[vec_ip_sorted[1].first], vpColor::red, 1,
512  false);
513  vpDisplay::displayLine(I, vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first], vpColor::red, 1,
514  false);
515 
516  }
517  else {
518  std::stringstream sserr;
519  sserr << "Failed to detect an Apriltag, or detected multiple ones";
520  vpDisplay::displayText(I, 120, 20, sserr.str(), vpColor::red);
521  vpDisplay::flush(I);
522  drone.stopMoving(); // In this case, we stop the drone
523  }
524 
525  vpDisplay::displayText(I, 10, 10, "Click to exit", vpColor::red);
526  vpDisplay::flush(I);
527  if (vpDisplay::getClick(I, false)) {
528  drone.land();
529  runLoop = false;
530  }
531 
532  plotter.plot(0, iter, task.getError());
533 
534  double totalTime = vpTime::measureTimeMs() - startTime;
535  std::stringstream sstime;
536  sstime << "Total time: " << totalTime << " ms";
537  vpDisplay::displayText(I, 80, 20, sstime.str(), vpColor::red);
538  vpDisplay::flush(I);
539 
540  iter++;
541  vpTime::wait(startTime, 40.0); // We wait a total of 40 milliseconds
542  }
543 
544  return EXIT_SUCCESS;
545 
546  }
547  else {
548  std::cout << "ERROR : failed to setup drone control." << std::endl;
549  return EXIT_FAILURE;
550  }
551  }
552  catch (const vpException &e) {
553  std::cout << "Caught an exception: " << e << std::endl;
554  return EXIT_FAILURE;
555  }
556 }
557 
558 #endif // #elif !defined(VISP_HAVE_FFMPEG)
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpRowVector t() const
static const vpColor red
Definition: vpColor.h:217
static const vpColor green
Definition: vpColor.h:220
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:133
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:135
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:60
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:242
unsigned int getHeight() const
Definition: vpImage.h:181
static double rad(double deg)
Definition: vpMath.h:129
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
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 which allows to u...
Definition: vpMomentBasic.h:73
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:114
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:112
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
void set_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:464
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:466
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:183
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:380
@ EYEINHAND_L_cVe_eJe
Definition: vpServo.h:168
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:331
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition: vpServo.h:1038
void setLambda(double c)
Definition: vpServo.h:986
void set_eJe(const vpMatrix &eJe_)
Definition: vpServo.h:1101
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:134
vpColVector getError() const
Definition: vpServo.h:510
vpColVector computeControlLaw()
Definition: vpServo.cpp:705
@ CURRENT
Definition: vpServo.h:202
Class that consider the case of a translation vector.
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 int wait(double t0, double t)
VISP_EXPORT double measureTimeMs()