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