Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
servoFlirPtuIBVS.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 * tests the control law
33 * eye-in-hand control
34 * velocity computed in the camera frame
35 *
36*****************************************************************************/
58#include <iostream>
59
60#include <visp3/core/vpCameraParameters.h>
61#include <visp3/core/vpXmlParserCamera.h>
62#include <visp3/detection/vpDetectorAprilTag.h>
63#include <visp3/gui/vpDisplayGDI.h>
64#include <visp3/gui/vpDisplayX.h>
65#include <visp3/gui/vpPlot.h>
66#include <visp3/io/vpImageIo.h>
67#include <visp3/robot/vpRobotFlirPtu.h>
68#include <visp3/sensor/vpFlyCaptureGrabber.h>
69#include <visp3/visual_features/vpFeatureBuilder.h>
70#include <visp3/visual_features/vpFeaturePoint.h>
71#include <visp3/vs/vpServo.h>
72#include <visp3/vs/vpServoDisplay.h>
73
74#if defined(VISP_HAVE_FLIR_PTU_SDK) && defined(VISP_HAVE_FLYCAPTURE) && \
75 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
76
77void display_point_trajectory(const vpImage<unsigned char> &I, const vpImagePoint &ip,
78 std::vector<vpImagePoint> &traj_ip)
79{
80 if (traj_ip.size()) {
81 // Add the point only if distance with the previous > 2 pixel
82 if (vpImagePoint::distance(ip, traj_ip.back()) > 2.) {
83 traj_ip.push_back(ip);
84 }
85 } else {
86 traj_ip.push_back(ip);
87 }
88 for (size_t j = 1; j < traj_ip.size(); j++) {
89 vpDisplay::displayLine(I, traj_ip[j - 1], traj_ip[j], vpColor::green, 2);
90 }
91}
92
93int main(int argc, char **argv)
94{
95 std::string opt_portname;
96 int opt_baudrate = 9600;
97 bool opt_network = false;
98 std::string opt_extrinsic;
99 std::string opt_intrinsic;
100 std::string opt_camera_name;
101 bool display_tag = true;
102 int opt_quad_decimate = 2;
103 double opt_tag_size = 0.120; // Used to compute the distance of the cog wrt the camera
104 bool opt_verbose = false;
105 bool opt_plot = false;
106 bool opt_adaptive_gain = false;
107 bool opt_task_sequencing = false;
108 double opt_constant_gain = 0.5;
109 bool opt_display_trajectory = true;
110 double convergence_threshold = 0.00005;
111
112 if (argc == 1) {
113 std::cout << "To see how to use this example, run: " << argv[0] << " --help" << std::endl;
114 return EXIT_SUCCESS;
115 }
116
117 for (int i = 1; i < argc; i++) {
118 if ((std::string(argv[i]) == "--portname" || std::string(argv[i]) == "-p") && (i + 1 < argc)) {
119 opt_portname = std::string(argv[i + 1]);
120 } else if ((std::string(argv[i]) == "--baudrate" || std::string(argv[i]) == "-b") && (i + 1 < argc)) {
121 opt_baudrate = std::atoi(argv[i + 1]);
122 } else if ((std::string(argv[i]) == "--network" || std::string(argv[i]) == "-n")) {
123 opt_network = true;
124 } else if (std::string(argv[i]) == "--extrinsic" && i + 1 < argc) {
125 opt_extrinsic = std::string(argv[i + 1]);
126 } else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) {
127 opt_intrinsic = std::string(argv[i + 1]);
128 } else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) {
129 opt_camera_name = std::string(argv[i + 1]);
130 } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
131 opt_verbose = true;
132 } else if (std::string(argv[i]) == "--plot" || std::string(argv[i]) == "-p") {
133 opt_plot = true;
134 } else if (std::string(argv[i]) == "--display-image-trajectory" || std::string(argv[i]) == "-traj") {
135 opt_display_trajectory = true;
136 } else if (std::string(argv[i]) == "--adaptive-gain" || std::string(argv[i]) == "-a") {
137 opt_adaptive_gain = true;
138 } else if (std::string(argv[i]) == "--constant-gain" || std::string(argv[i]) == "-g") {
139 opt_constant_gain = std::stod(argv[i + 1]);
140 } else if (std::string(argv[i]) == "--task-sequencing") {
141 opt_task_sequencing = true;
142 } else if (std::string(argv[i]) == "--quad-decimate" && i + 1 < argc) {
143 opt_quad_decimate = std::stoi(argv[i + 1]);
144 }
145 if (std::string(argv[i]) == "--tag-size" && i + 1 < argc) {
146 opt_tag_size = std::stod(argv[i + 1]);
147 } else if (std::string(argv[i]) == "--no-convergence-threshold") {
148 convergence_threshold = 0.;
149 } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
150 std::cout << "SYNOPSIS" << std::endl
151 << " " << argv[0] << " [--portname <portname>] [--baudrate <rate>] [--network] "
152 << "[--extrinsic <extrinsic.yaml>] [--intrinsic <intrinsic.xml>] [--camera-name <name>] "
153 << "[--quad-decimate <decimation>] [--tag-size <size>] "
154 << "[--adaptive-gain] [--constant-gain] [--display-image-trajectory] [--plot] [--task-sequencing] "
155 << "[--no-convergence-threshold] [--verbose] [--help] [-h]" << std::endl
156 << std::endl;
157 std::cout << "DESCRIPTION" << std::endl
158 << " --portname, -p <portname>" << std::endl
159 << " Set serial or tcp port name." << std::endl
160 << std::endl
161 << " --baudrate, -b <rate>" << std::endl
162 << " Set serial communication baud rate. Default: " << opt_baudrate << "." << std::endl
163 << std::endl
164 << " --network, -n" << std::endl
165 << " Get PTU network information (Hostname, IP, Gateway) and exit. " << std::endl
166 << std::endl
167 << " --reset, -r" << std::endl
168 << " Reset PTU axis and exit. " << std::endl
169 << std::endl
170 << " --extrinsic <extrinsic.yaml>" << std::endl
171 << " YAML file containing extrinsic camera parameters as a vpHomogeneousMatrix." << std::endl
172 << " It corresponds to the homogeneous transformation eMc, between end-effector" << std::endl
173 << " and camera frame." << std::endl
174 << std::endl
175 << " --intrinsic <intrinsic.xml>" << std::endl
176 << " Intrinsic camera parameters obtained after camera calibration." << std::endl
177 << std::endl
178 << " --camera-name <name>" << std::endl
179 << " Name of the camera to consider in the xml file provided for intrinsic camera parameters."
180 << std::endl
181 << std::endl
182 << " --quad-decimate <decimation>" << std::endl
183 << " Decimation factor used to detect AprilTag. Default " << opt_quad_decimate << "." << std::endl
184 << std::endl
185 << " --tag-size <size>" << std::endl
186 << " Width in meter or the black part of the AprilTag used as target. Default " << opt_tag_size
187 << "." << std::endl
188 << std::endl
189 << " --adaptive-gain, -a" << std::endl
190 << " Enable adaptive gain instead of constant gain to speed up convergence. " << std::endl
191 << std::endl
192 << " --constant-gain, -g" << std::endl
193 << " Constant gain value. Default value: " << opt_constant_gain << std::endl
194 << std::endl
195 << " --display-image-trajectory, -traj" << std::endl
196 << " Display the trajectory of the target cog in the image. " << std::endl
197 << std::endl
198 << " --plot, -p" << std::endl
199 << " Enable curve plotter. " << std::endl
200 << std::endl
201 << " --task-sequencing" << std::endl
202 << " Enable task sequencing that allows to smoothly control the velocity of the robot. " << std::endl
203 << std::endl
204 << " --no-convergence-threshold" << std::endl
205 << " Disable ending servoing when it reaches the desired position." << std::endl
206 << std::endl
207 << " --verbose, -v" << std::endl
208 << " Additional printings. " << std::endl
209 << std::endl
210 << " --help, -h" << std::endl
211 << " Print this helper message. " << std::endl
212 << std::endl;
213 std::cout << "EXAMPLE" << std::endl
214 << " - How to get network IP" << std::endl
215#ifdef _WIN32
216 << " $ " << argv[0] << " --portname COM1 --network" << std::endl
217 << " Try to connect FLIR PTU to port: COM1 with baudrate: 9600" << std::endl
218#else
219 << " $ " << argv[0] << " -p /dev/ttyUSB0 --network" << std::endl
220 << " Try to connect FLIR PTU to port: /dev/ttyUSB0 with baudrate: 9600" << std::endl
221#endif
222 << " PTU HostName: PTU-5" << std::endl
223 << " PTU IP : 169.254.110.254" << std::endl
224 << " PTU Gateway : 0.0.0.0" << std::endl
225 << " - How to run this binary using network communication" << std::endl
226 << " $ " << argv[0] << " --portname tcp:169.254.110.254 --tag-size 0.1 --gain 0.1" << std::endl;
227
228 return EXIT_SUCCESS;
229 }
230 }
231
232 vpRobotFlirPtu robot;
233
234 try {
235 std::cout << "Try to connect FLIR PTU to port: " << opt_portname << " with baudrate: " << opt_baudrate << std::endl;
236 robot.connect(opt_portname, opt_baudrate);
237
238 if (opt_network) {
239 std::cout << "PTU HostName: " << robot.getNetworkHostName() << std::endl;
240 std::cout << "PTU IP : " << robot.getNetworkIP() << std::endl;
241 std::cout << "PTU Gateway : " << robot.getNetworkGateway() << std::endl;
242 return EXIT_SUCCESS;
243 }
244
246
248 g.open(I);
249
250 // Get camera extrinsics
253 eRc << 0, 0, 1, -1, 0, 0, 0, -1, 0;
254 etc << -0.1, -0.123, 0.035;
255 vpHomogeneousMatrix eMc(etc, eRc);
256
257 // If provided, read camera extrinsics from command line option
258 if (!opt_extrinsic.empty()) {
259 vpPoseVector ePc;
260 ePc.loadYAML(opt_extrinsic, ePc);
261 eMc.buildFrom(ePc);
262 } else {
263 std::cout << "***************************************************************" << std::endl;
264 std::cout << "Warning, use hard coded values for extrinsic camera parameters." << std::endl;
265 std::cout << "Create a yaml file that contains the extrinsic:" << std::endl
266 << std::endl
267 << "$ cat eMc.yaml" << std::endl
268 << "rows: 4" << std::endl
269 << "cols: 4" << std::endl
270 << "data:" << std::endl
271 << " - [0, 0, 1, -0.1]" << std::endl
272 << " - [-1, 0, 0, -0.123]" << std::endl
273 << " - [0, -1, 0, 0.035]" << std::endl
274 << " - [0, 0, 0, 1]" << std::endl
275 << std::endl
276 << "and load this file with [--extrinsic <extrinsic.yaml] command line option, like:" << std::endl
277 << std::endl
278 << "$ " << argv[0] << "-p " << opt_portname << " --extrinsic eMc.yaml" << std::endl
279 << std::endl;
280 std::cout << "***************************************************************" << std::endl;
281 }
282
283 std::cout << "Considered extrinsic transformation eMc:\n" << eMc << std::endl;
284
285 // Get camera intrinsics
286 vpCameraParameters cam(900, 900, I.getWidth() / 2., I.getHeight() / 2.);
287
288 // If provided, read camera intrinsics from command line option
289 if (!opt_intrinsic.empty() && !opt_camera_name.empty()) {
290 vpXmlParserCamera parser;
291 parser.parse(cam, opt_intrinsic, opt_camera_name, vpCameraParameters::perspectiveProjWithoutDistortion);
292 } else {
293 std::cout << "***************************************************************" << std::endl;
294 std::cout << "Warning, use hard coded values for intrinsic camera parameters." << std::endl;
295 std::cout << "Calibrate your camera and load the parameters from command line options, like:" << std::endl
296 << std::endl
297 << "$ " << argv[0] << "-p " << opt_portname << " --intrinsic camera.xml --camera-name \"Camera\""
298 << std::endl
299 << std::endl;
300 std::cout << "***************************************************************" << std::endl;
301 }
302
303 std::cout << "Considered intrinsic camera parameters:\n" << cam << "\n";
304
305#if defined(VISP_HAVE_X11)
306 vpDisplayX dc(I, 10, 10, "Color image");
307#elif defined(VISP_HAVE_GDI)
308 vpDisplayGDI dc(I, 10, 10, "Color image");
309#endif
310
313 vpDetectorAprilTag detector(tagFamily);
314 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
315 detector.setDisplayTag(display_tag);
316 detector.setAprilTagQuadDecimate(opt_quad_decimate);
317
318 // Create visual features
319 vpFeaturePoint p, pd; // We use 1 point, the tag cog
320
321 // Set desired position to the image center
322 pd.set_x(0);
323 pd.set_y(0);
324
325 vpServo task;
326 // Add the visual feature point
327 task.addFeature(p, pd);
330
331 if (opt_adaptive_gain) {
332 vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
333 task.setLambda(lambda);
334 } else {
335 task.setLambda(opt_constant_gain);
336 }
337
338 vpPlot *plotter = nullptr;
339 int iter_plot = 0;
340
341 if (opt_plot) {
342 plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
343 "Real time curves plotter");
344 plotter->setTitle(0, "Visual features error");
345 plotter->setTitle(1, "Joint velocities");
346 plotter->initGraph(0, 2);
347 plotter->initGraph(1, 2);
348 plotter->setLegend(0, 0, "error_feat_p_x");
349 plotter->setLegend(0, 1, "error_feat_p_y");
350 plotter->setLegend(1, 0, "qdot_pan");
351 plotter->setLegend(1, 1, "qdot_tilt");
352 }
353
354 bool final_quit = false;
355 bool has_converged = false;
356 bool send_velocities = false;
357 bool servo_started = false;
358 std::vector<vpImagePoint> traj_cog;
359 vpMatrix eJe;
360
361 static double t_init_servo = vpTime::measureTimeMs();
362
363 robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
364
365 vpVelocityTwistMatrix cVe = robot.get_cVe();
366 std::cout << cVe << std::endl;
367 task.set_cVe(cVe);
368
370
371 while (!has_converged && !final_quit) {
372 double t_start = vpTime::measureTimeMs();
373
374 g.acquire(I);
375
377
378 std::vector<vpHomogeneousMatrix> cMo_vec;
379 detector.detect(I, opt_tag_size, cam, cMo_vec);
380
381 std::stringstream ss;
382 ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
383 vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
384
385 vpColVector qdot(2);
386
387 // Only one tag has to be detected
388 if (detector.getNbObjects() == 1) {
389
390 vpImagePoint cog = detector.getCog(0);
391 double Z = cMo_vec[0][2][3];
392
393 // Update current feature from measured cog position
394 double x = 0, y = 0;
396 if (opt_verbose) {
397 std::cout << "Z: " << Z << std::endl;
398 }
399 p.set_xyZ(x, y, Z);
400 pd.set_Z(Z);
401
402 // Get robot Jacobian
403 robot.get_eJe(eJe);
404 task.set_eJe(eJe);
405
406 if (opt_task_sequencing) {
407 if (!servo_started) {
408 if (send_velocities) {
409 servo_started = true;
410 }
411 t_init_servo = vpTime::measureTimeMs();
412 }
413 qdot = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
414 } else {
415 qdot = task.computeControlLaw();
416 }
417
418 // Display the current and desired feature points in the image display
420
421 // Display the trajectory of the points used as features
422 if (opt_display_trajectory) {
423 display_point_trajectory(I, cog, traj_cog);
424 }
425
426 if (opt_plot) {
427 plotter->plot(0, iter_plot, task.getError());
428 plotter->plot(1, iter_plot, qdot);
429 iter_plot++;
430 }
431
432 if (opt_verbose) {
433 std::cout << "qdot: " << qdot.t() << std::endl;
434 }
435
436 double error = task.getError().sumSquare();
437 ss.str("");
438 ss << "error: " << error;
439 vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
440
441 if (opt_verbose)
442 std::cout << "error: " << error << std::endl;
443
444 if (error < convergence_threshold) {
445 has_converged = true;
446 std::cout << "Servo task has converged"
447 << "\n";
448 vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
449 }
450 } // end if (cMo_vec.size() == 1)
451 else {
452 qdot = 0;
453 }
454
455 if (!send_velocities) {
456 qdot = 0;
457 }
458
459 // Send to the robot
461 ss.str("");
462 ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
463 vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
464
466
468 if (vpDisplay::getClick(I, button, false)) {
469 switch (button) {
471 send_velocities = !send_velocities;
472 break;
473
475 final_quit = true;
476 qdot = 0;
477 break;
478
479 default:
480 break;
481 }
482 }
483 }
484 std::cout << "Stop the robot " << std::endl;
486
487 if (opt_plot && plotter != nullptr) {
488 delete plotter;
489 plotter = nullptr;
490 }
491
492 if (!final_quit) {
493 while (!final_quit) {
494 g.acquire(I);
496
497 vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
498 vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
499
500 if (vpDisplay::getClick(I, false)) {
501 final_quit = true;
502 }
503
505 }
506 }
507 } catch (const vpRobotException &e) {
508 std::cout << "Catch Flir Ptu signal exception: " << e.getMessage() << std::endl;
510 } catch (const vpException &e) {
511 std::cout << "ViSP exception: " << e.what() << std::endl;
512 std::cout << "Stop the robot " << std::endl;
514 }
515
516 return EXIT_SUCCESS;
517}
518#else
519int main()
520{
521#if !defined(VISP_HAVE_FLYCAPTURE)
522 std::cout << "Install FLIR Flycapture" << std::endl;
523#endif
524#if !defined(VISP_HAVE_FLIR_PTU_SDK)
525 std::cout << "Install FLIR PTU SDK." << std::endl;
526#endif
527 return EXIT_SUCCESS;
528}
529#endif
Adaptive gain computation.
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
Definition vpArray2D.h:696
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
double sumSquare() 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).
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition vpDisplayX.h:132
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 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:59
const char * getMessage() const
const char * what() const
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
void set_xyZ(double x, double y, double Z)
void set_y(double y)
void set_x(double x)
void set_Z(double Z)
void open(vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &I)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
Definition of the vpImage class member functions.
Definition vpImage.h:135
unsigned int getWidth() const
Definition vpImage.h:242
unsigned int getHeight() const
Definition vpImage.h:184
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:152
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:113
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition vpPlot.cpp:202
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
Definition vpPlot.cpp:545
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
Definition vpPlot.cpp:269
void setTitle(unsigned int graphNum, const std::string &title)
Definition vpPlot.cpp:503
Implementation of a pose vector and operations on poses.
Error that can be emitted by the vpRobot class and its derivatives.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
void get_eJe(vpMatrix &eJe)
@ JOINT_STATE
Definition vpRobot.h:78
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:198
Implementation of a rotation matrix and operations on such kind of matrices.
static void display(const vpServo &s, const vpCameraParameters &cam, const vpImage< unsigned char > &I, vpColor currentColor=vpColor::green, vpColor desiredColor=vpColor::red, unsigned int thickness=1)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition vpServo.cpp:564
@ EYEINHAND_L_cVe_eJe
Definition vpServo.h:155
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition vpServo.h:448
void setLambda(double c)
Definition vpServo.h:403
void set_eJe(const vpMatrix &eJe_)
Definition vpServo.h:506
void setServo(const vpServoType &servo_type)
Definition vpServo.cpp:210
vpColVector getError() const
Definition vpServo.h:276
vpColVector computeControlLaw()
Definition vpServo.cpp:930
@ CURRENT
Definition vpServo.h:179
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition vpServo.cpp:487
Class that consider the case of a translation vector.
vpVelocityTwistMatrix get_cVe() const
Definition vpUnicycle.h:79
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()