Visual Servoing Platform  version 3.4.0
vpCalibration.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Camera calibration.
33  *
34  * Authors:
35  * Eric Marchand
36  * Francois Chaumette
37  * Anthony Saunier
38  *
39  *****************************************************************************/
40 
46 #include <visp3/core/vpDebug.h>
47 #include <visp3/core/vpPixelMeterConversion.h>
48 #include <visp3/vision/vpCalibration.h>
49 #include <visp3/vision/vpPose.h>
50 
51 double vpCalibration::threshold = 1e-10f;
52 unsigned int vpCalibration::nbIterMax = 4000;
53 double vpCalibration::gain = 0.25;
58 {
59  npt = 0;
60 
61  residual = residual_dist = 1000.;
62 
63  LoX.clear();
64  LoY.clear();
65  LoZ.clear();
66  Lip.clear();
67 
68  return 0;
69 }
70 
75  : cMo(), cMo_dist(), cam(), cam_dist(), rMe(), eMc(), eMc_dist(), npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.),
76  residual_dist(1000.)
77 {
78  init();
79 }
84  : cMo(), cMo_dist(), cam(), cam_dist(), rMe(), eMc(), eMc_dist(), npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.),
85  residual_dist(1000.)
86 {
87  (*this) = c;
88 }
89 
94 
101 {
102  npt = twinCalibration.npt;
103  LoX = twinCalibration.LoX;
104  LoY = twinCalibration.LoY;
105  LoZ = twinCalibration.LoZ;
106  Lip = twinCalibration.Lip;
107 
108  residual = twinCalibration.residual;
109  cMo = twinCalibration.cMo;
110  residual_dist = twinCalibration.residual_dist;
111  cMo_dist = twinCalibration.cMo_dist;
112 
113  cam = twinCalibration.cam;
114  cam_dist = twinCalibration.cam_dist;
115 
116  rMe = twinCalibration.rMe;
117 
118  eMc = twinCalibration.eMc;
119  eMc_dist = twinCalibration.eMc_dist;
120 
121  return (*this);
122 }
123 
128 {
129  LoX.clear();
130  LoY.clear();
131  LoZ.clear();
132  Lip.clear();
133  npt = 0;
134 
135  return 0;
136 }
137 
144 int vpCalibration::addPoint(double X, double Y, double Z, vpImagePoint &ip)
145 {
146  LoX.push_back(X);
147  LoY.push_back(Y);
148  LoZ.push_back(Z);
149 
150  Lip.push_back(ip);
151 
152  npt++;
153 
154  return 0;
155 }
156 
162 void vpCalibration::computePose(const vpCameraParameters &camera, vpHomogeneousMatrix &cMo_est)
163 {
164  // The vpPose class mainly contents a list of vpPoint (that is (X,Y,Z, x, y)
165  // )
166  vpPose pose;
167  // the list of point is cleared (if that's not done before)
168  pose.clearPoint();
169  // we set the 3D points coordinates (in meter !) in the object/world frame
170  std::list<double>::const_iterator it_LoX = LoX.begin();
171  std::list<double>::const_iterator it_LoY = LoY.begin();
172  std::list<double>::const_iterator it_LoZ = LoZ.begin();
173  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
174 
175  for (unsigned int i = 0; i < npt; i++) {
176  vpPoint P(*it_LoX, *it_LoY, *it_LoZ);
177  double x = 0, y = 0;
178  vpPixelMeterConversion::convertPoint(camera, *it_Lip, x, y);
179  P.set_x(x);
180  P.set_y(y);
181 
182  pose.addPoint(P);
183  ++it_LoX;
184  ++it_LoY;
185  ++it_LoZ;
186  ++it_Lip;
187  }
188  vpHomogeneousMatrix cMo_dementhon; // computed pose with dementhon
189  vpHomogeneousMatrix cMo_lagrange; // computed pose with dementhon
190 
191  // compute the initial pose using Lagrange method followed by a non linear
192  // minimisation method
193  // Pose by Lagrange it provides an initialization of the pose
194  double residual_lagrange = std::numeric_limits<double>::max();
195  double residual_dementhon = std::numeric_limits<double>::max();
196  try {
197  pose.computePose(vpPose::LAGRANGE, cMo_lagrange);
198  residual_lagrange = pose.computeResidual(cMo_lagrange);
199  }
200  catch(const vpException &e) {
201  std::cout << "Pose from Lagrange exception: " << e.getMessage() << std::endl;
202  }
203 
204  // compute the initial pose using Dementhon method followed by a non linear
205  // minimisation method
206  // Pose by Dementhon it provides an initialization of the pose
207  try {
208  pose.computePose(vpPose::DEMENTHON, cMo_dementhon);
209  residual_dementhon = pose.computeResidual(cMo_dementhon);
210  }
211  catch(const vpException &e) {
212  std::cout << "Pose from Dementhon exception: " << e.getMessage() << std::endl;
213  }
214 
215  // we keep the better initialization
216  if (residual_lagrange < residual_dementhon)
217  cMo_est = cMo_lagrange;
218  else
219  cMo_est = cMo_dementhon;
220 
221  // the pose is now refined using the virtual visual servoing approach
222  // Warning: cMo needs to be initialized otherwise it may diverge
223  pose.computePose(vpPose::VIRTUAL_VS, cMo_est);
224 }
225 
234 {
235  double residual_ = 0;
236 
237  std::list<double>::const_iterator it_LoX = LoX.begin();
238  std::list<double>::const_iterator it_LoY = LoY.begin();
239  std::list<double>::const_iterator it_LoZ = LoZ.begin();
240  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
241 
242  double u0 = camera.get_u0();
243  double v0 = camera.get_v0();
244  double px = camera.get_px();
245  double py = camera.get_py();
246  vpImagePoint ip;
247 
248  for (unsigned int i = 0; i < npt; i++) {
249  double oX = *it_LoX;
250  double oY = *it_LoY;
251  double oZ = *it_LoZ;
252 
253  double cX = oX * cMo_est[0][0] + oY * cMo_est[0][1] + oZ * cMo_est[0][2] + cMo_est[0][3];
254  double cY = oX * cMo_est[1][0] + oY * cMo_est[1][1] + oZ * cMo_est[1][2] + cMo_est[1][3];
255  double cZ = oX * cMo_est[2][0] + oY * cMo_est[2][1] + oZ * cMo_est[2][2] + cMo_est[2][3];
256 
257  double x = cX / cZ;
258  double y = cY / cZ;
259 
260  ip = *it_Lip;
261  double u = ip.get_u();
262  double v = ip.get_v();
263 
264  double xp = u0 + x * px;
265  double yp = v0 + y * py;
266 
267  residual_ += (vpMath::sqr(xp - u) + vpMath::sqr(yp - v));
268 
269  ++it_LoX;
270  ++it_LoY;
271  ++it_LoZ;
272  ++it_Lip;
273  }
274  this->residual = residual_;
275  return sqrt(residual_ / npt);
276 }
285 {
286  double residual_ = 0;
287 
288  std::list<double>::const_iterator it_LoX = LoX.begin();
289  std::list<double>::const_iterator it_LoY = LoY.begin();
290  std::list<double>::const_iterator it_LoZ = LoZ.begin();
291  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
292 
293  double u0 = camera.get_u0();
294  double v0 = camera.get_v0();
295  double px = camera.get_px();
296  double py = camera.get_py();
297  double kud = camera.get_kud();
298  double kdu = camera.get_kdu();
299 
300  double inv_px = 1 / px;
301  double inv_py = 1 / px;
302  vpImagePoint ip;
303 
304  for (unsigned int i = 0; i < npt; i++) {
305  double oX = *it_LoX;
306  double oY = *it_LoY;
307  double oZ = *it_LoZ;
308 
309  double cX = oX * cMo_est[0][0] + oY * cMo_est[0][1] + oZ * cMo_est[0][2] + cMo_est[0][3];
310  double cY = oX * cMo_est[1][0] + oY * cMo_est[1][1] + oZ * cMo_est[1][2] + cMo_est[1][3];
311  double cZ = oX * cMo_est[2][0] + oY * cMo_est[2][1] + oZ * cMo_est[2][2] + cMo_est[2][3];
312 
313  double x = cX / cZ;
314  double y = cY / cZ;
315 
316  ip = *it_Lip;
317  double u = ip.get_u();
318  double v = ip.get_v();
319 
320  double r2ud = 1 + kud * (vpMath::sqr(x) + vpMath::sqr(y));
321 
322  double xp = u0 + x * px * r2ud;
323  double yp = v0 + y * py * r2ud;
324 
325  residual_ += (vpMath::sqr(xp - u) + vpMath::sqr(yp - v));
326 
327  double r2du = (vpMath::sqr((u - u0) * inv_px) + vpMath::sqr((v - v0) * inv_py));
328 
329  xp = u0 + x * px - kdu * (u - u0) * r2du;
330  yp = v0 + y * py - kdu * (v - v0) * r2du;
331 
332  residual_ += (vpMath::sqr(xp - u) + vpMath::sqr(yp - v));
333  ++it_LoX;
334  ++it_LoY;
335  ++it_LoZ;
336  ++it_Lip;
337  }
338  residual_ /= 2;
339 
340  this->residual_dist = residual_;
341  return sqrt(residual_ / npt);
342 }
343 
351 void vpCalibration::computeStdDeviation(double &deviation, double &deviation_dist)
352 {
353  deviation = computeStdDeviation(cMo, cam);
354  deviation_dist = computeStdDeviation_dist(cMo_dist, cam_dist);
355 }
356 
369  vpCameraParameters &cam_est, bool verbose)
370 {
371  try {
372  computePose(cam_est, cMo_est);
373  switch (method) {
374  case CALIB_LAGRANGE:
376  calibLagrange(cam_est, cMo_est);
377  } break;
378  case CALIB_VIRTUAL_VS:
381  default:
382  break;
383  }
384 
385  switch (method) {
386  case CALIB_VIRTUAL_VS:
390  if (verbose) {
391  std::cout << "start calibration without distortion" << std::endl;
392  }
393  calibVVS(cam_est, cMo_est, verbose);
394  } break;
395  case CALIB_LAGRANGE:
396  default:
397  break;
398  }
399  this->cMo = cMo_est;
400  this->cMo_dist = cMo_est;
401 
402  // Print camera parameters
403  if (verbose) {
404  // std::cout << "Camera parameters without distortion :" <<
405  // std::endl;
406  cam_est.printParameters();
407  }
408 
409  this->cam = cam_est;
410 
411  switch (method) {
414  if (verbose) {
415  std::cout << "start calibration with distortion" << std::endl;
416  }
417  calibVVSWithDistortion(cam_est, cMo_est, verbose);
418  } break;
419  case CALIB_LAGRANGE:
420  case CALIB_VIRTUAL_VS:
422  default:
423  break;
424  }
425  // Print camera parameters
426  if (verbose) {
427  // std::cout << "Camera parameters without distortion :" <<
428  // std::endl;
429  this->cam.printParameters();
430  // std::cout << "Camera parameters with distortion :" <<
431  // std::endl;
432  cam_est.printParameters();
433  }
434 
435  this->cam_dist = cam_est;
436 
437  this->cMo_dist = cMo_est;
438 
439  if (cam_est.get_px() < 0 || cam_est.get_py() < 0 || cam_est.get_u0() < 0 || cam_est.get_v0() < 0) {
440  if (verbose) {
441  std::cout << "Unable to calibrate the camera. Estimated parameters are negative." << std::endl;
442  }
443  return EXIT_FAILURE;
444  }
445 
446  return EXIT_SUCCESS;
447  } catch (...) {
448  throw;
449  }
450 }
451 
466 int vpCalibration::computeCalibrationMulti(vpCalibrationMethodType method, std::vector<vpCalibration> &table_cal,
467  vpCameraParameters &cam_est, double &globalReprojectionError, bool verbose)
468 {
469  try {
470  unsigned int nbPose = (unsigned int)table_cal.size();
471  for (unsigned int i = 0; i < nbPose; i++) {
472  if (table_cal[i].get_npt() > 3)
473  table_cal[i].computePose(cam_est, table_cal[i].cMo);
474  }
475  switch (method) {
476  case CALIB_LAGRANGE: {
477  if (nbPose > 1) {
478  std::cout << "this calibration method is not available in" << std::endl
479  << "vpCalibration::computeCalibrationMulti()" << std::endl;
480  return -1;
481  } else {
482  table_cal[0].calibLagrange(cam_est, table_cal[0].cMo);
483  table_cal[0].cam = cam_est;
484  table_cal[0].cam_dist = cam_est;
485  table_cal[0].cMo_dist = table_cal[0].cMo;
486  }
487  break;
488  }
491  if (nbPose > 1) {
492  std::cout << "this calibration method is not available in" << std::endl
493  << "vpCalibration::computeCalibrationMulti()" << std::endl
494  << "with several images." << std::endl;
495  return -1;
496  } else {
497  table_cal[0].calibLagrange(cam_est, table_cal[0].cMo);
498  table_cal[0].cam = cam_est;
499  table_cal[0].cam_dist = cam_est;
500  table_cal[0].cMo_dist = table_cal[0].cMo;
501  }
502  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
503  break;
504  }
505  case CALIB_VIRTUAL_VS:
506  case CALIB_VIRTUAL_VS_DIST: {
507  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
508  break;
509  }
510  }
511  // Print camera parameters
512  if (verbose) {
513  // std::cout << "Camera parameters without distortion :" <<
514  // std::endl;
515  cam_est.printParameters();
516  }
517 
518  switch (method) {
519  case CALIB_LAGRANGE:
521  case CALIB_VIRTUAL_VS:
522  verbose = false;
523  break;
525  case CALIB_VIRTUAL_VS_DIST: {
526  if (verbose)
527  std::cout << "Compute camera parameters with distortion" << std::endl;
528 
529  calibVVSWithDistortionMulti(table_cal, cam_est, globalReprojectionError, verbose);
530  } break;
531  }
532  // Print camera parameters
533  if (verbose) {
534  // std::cout << "Camera parameters without distortion :" <<
535  // std::endl;
536  table_cal[0].cam.printParameters();
537  // std::cout << "Camera parameters with distortion:" << std::endl;
538  cam_est.printParameters();
539  std::cout << std::endl;
540  }
541 
542  if (cam_est.get_px() < 0 || cam_est.get_py() < 0 || cam_est.get_u0() < 0 || cam_est.get_v0() < 0) {
543  if (verbose) {
544  std::cout << "Unable to calibrate the camera. Estimated parameters are negative." << std::endl;
545  }
546  return EXIT_FAILURE;
547  }
548 
549  return EXIT_SUCCESS;
550  } catch (...) {
551  throw;
552  }
553 }
554 
562 int vpCalibration::writeData(const char *filename)
563 {
564  std::ofstream f(filename);
565  vpImagePoint ip;
566 
567  std::list<double>::const_iterator it_LoX = LoX.begin();
568  std::list<double>::const_iterator it_LoY = LoY.begin();
569  std::list<double>::const_iterator it_LoZ = LoZ.begin();
570  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
571 
572  f.precision(10);
573  f.setf(std::ios::fixed, std::ios::floatfield);
574  f << LoX.size() << std::endl;
575 
576  for (unsigned int i = 0; i < LoX.size(); i++) {
577 
578  double oX = *it_LoX;
579  double oY = *it_LoY;
580  double oZ = *it_LoZ;
581 
582  ip = *it_Lip;
583  double u = ip.get_u();
584  double v = ip.get_v();
585 
586  f << oX << " " << oY << " " << oZ << " " << u << " " << v << std::endl;
587 
588  ++it_LoX;
589  ++it_LoY;
590  ++it_LoZ;
591  ++it_Lip;
592  }
593 
594  f.close();
595  return 0;
596 }
597 
604 int vpCalibration::readData(const char *filename)
605 {
606  vpImagePoint ip;
607  std::ifstream f;
608  f.open(filename);
609  if (!f.fail()) {
610  unsigned int n;
611  f >> n;
612  std::cout << "There are " << n << " point on the calibration grid " << std::endl;
613 
614  clearPoint();
615 
616  if (n > 100000)
617  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
618 
619  for (unsigned int i = 0; i < n; i++) {
620  double x, y, z, u, v;
621  f >> x >> y >> z >> u >> v;
622  std::cout << x << " " << y << " " << z << " " << u << " " << v << std::endl;
623  ip.set_u(u);
624  ip.set_v(v);
625  addPoint(x, y, z, ip);
626  }
627 
628  f.close();
629  return 0;
630  } else {
631  return -1;
632  }
633 }
650 int vpCalibration::readGrid(const char *filename, unsigned int &n, std::list<double> &oX, std::list<double> &oY,
651  std::list<double> &oZ, bool verbose)
652 {
653  try {
654  std::ifstream f;
655  f.open(filename);
656  if (!f.fail()) {
657 
658  f >> n;
659  if (verbose)
660  std::cout << "There are " << n << " points on the calibration grid " << std::endl;
661  int no_pt;
662  double x, y, z;
663 
664  // clear the list
665  oX.clear();
666  oY.clear();
667  oZ.clear();
668 
669  if (n > 100000)
670  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
671 
672  for (unsigned int i = 0; i < n; i++) {
673  f >> no_pt >> x >> y >> z;
674  if (verbose) {
675  std::cout << no_pt << std::endl;
676  std::cout << x << " " << y << " " << z << std::endl;
677  }
678  oX.push_back(x);
679  oY.push_back(y);
680  oZ.push_back(z);
681  }
682 
683  f.close();
684  } else {
685  return -1;
686  }
687  } catch (...) {
688  return -1;
689  }
690  return 0;
691 }
692 
703 int vpCalibration::displayData(vpImage<unsigned char> &I, vpColor color, unsigned int thickness, int subsampling_factor)
704 {
705 
706  for (std::list<vpImagePoint>::const_iterator it = Lip.begin(); it != Lip.end(); ++it) {
707  vpImagePoint ip = *it;
708  if (subsampling_factor > 1.) {
709  ip.set_u(ip.get_u() / subsampling_factor);
710  ip.set_v(ip.get_v() / subsampling_factor);
711  }
712  vpDisplay::displayCross(I, ip, 12, color, thickness);
713  }
714  return 0;
715 }
716 
727 int vpCalibration::displayGrid(vpImage<unsigned char> &I, vpColor color, unsigned int thickness, int subsampling_factor)
728 {
729  double u0_dist = cam_dist.get_u0() / subsampling_factor;
730  double v0_dist = cam_dist.get_v0() / subsampling_factor;
731  double px_dist = cam_dist.get_px() / subsampling_factor;
732  double py_dist = cam_dist.get_py() / subsampling_factor;
733  double kud_dist = cam_dist.get_kud();
734  // double kdu_dist = cam_dist.get_kdu() ;
735 
736  // double u0 = cam.get_u0() ;
737  // double v0 = cam.get_v0() ;
738  // double px = cam.get_px() ;
739  // double py = cam.get_py() ;
740 
741  std::list<double>::const_iterator it_LoX = LoX.begin();
742  std::list<double>::const_iterator it_LoY = LoY.begin();
743  std::list<double>::const_iterator it_LoZ = LoZ.begin();
744 
745  for (unsigned int i = 0; i < npt; i++) {
746  double oX = *it_LoX;
747  double oY = *it_LoY;
748  double oZ = *it_LoZ;
749 
750  // double cX = oX*cMo[0][0]+oY*cMo[0][1]+oZ*cMo[0][2] + cMo[0][3];
751  // double cY = oX*cMo[1][0]+oY*cMo[1][1]+oZ*cMo[1][2] + cMo[1][3];
752  // double cZ = oX*cMo[2][0]+oY*cMo[2][1]+oZ*cMo[2][2] + cMo[2][3];
753 
754  // double x = cX/cZ ;
755  // double y = cY/cZ ;
756 
757  // double xp = u0 + x*px ;
758  // double yp = v0 + y*py ;
759 
760  // vpDisplay::displayCross(I,(int)vpMath::round(yp),
761  // (int)vpMath::round(xp),
762  // 5,col) ;
763 
764  double cX = oX * cMo_dist[0][0] + oY * cMo_dist[0][1] + oZ * cMo_dist[0][2] + cMo_dist[0][3];
765  double cY = oX * cMo_dist[1][0] + oY * cMo_dist[1][1] + oZ * cMo_dist[1][2] + cMo_dist[1][3];
766  double cZ = oX * cMo_dist[2][0] + oY * cMo_dist[2][1] + oZ * cMo_dist[2][2] + cMo_dist[2][3];
767 
768  double x = cX / cZ;
769  double y = cY / cZ;
770 
771  double r2 = 1 + kud_dist * (vpMath::sqr(x) + vpMath::sqr(y));
772 
773  vpImagePoint ip;
774  ip.set_u(u0_dist + x * px_dist * r2);
775  ip.set_v(v0_dist + y * py_dist * r2);
776 
777  vpDisplay::displayCross(I, ip, 6, color, thickness);
779 
780  // std::cout << oX << " " << oY << " " <<oZ << std::endl ;
781  // I.getClick() ;
782  ++it_LoX;
783  ++it_LoY;
784  ++it_LoZ;
785  }
786  return 0;
787 }
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:97
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(const vpHomogeneousMatrix &)=NULL)
Definition: vpPose.cpp:374
double get_v() const
Definition: vpImagePoint.h:273
double get_u0() const
int computeCalibration(vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false)
Implementation of an homogeneous matrix and operations on such kind of matrices.
void set_u(double u)
Definition: vpImagePoint.h:225
int readData(const char *filename)
Class to define RGB colors available for display functionnalities.
Definition: vpColor.h:157
double get_u() const
Definition: vpImagePoint.h:262
error that can be emited by ViSP classes.
Definition: vpException.h:71
int addPoint(double X, double Y, double Z, vpImagePoint &ip)
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
double get_py() const
Tools for perspective camera calibration.
Definition: vpCalibration.h:71
virtual ~vpCalibration()
vpHomogeneousMatrix cMo
(as a 3x4 matrix [R T])
Definition: vpCalibration.h:93
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:81
void set_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:497
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:499
vpCalibration & operator=(const vpCalibration &twinCalibration)
int clearPoint()
Suppress all the point in the array of point.
double get_v0() const
static double sqr(double x)
Definition: vpMath.h:116
int displayGrid(vpImage< unsigned char > &I, vpColor color=vpColor::yellow, unsigned int thickness=1, int subsampling_factor=1)
vpHomogeneousMatrix cMo_dist
Definition: vpCalibration.h:95
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:80
Generic class defining intrinsic camera parameters.
vpHomogeneousMatrix eMc_dist
Position of the camera in end-effector frame using camera parameters with distorsion.
unsigned int get_npt() const
get the number of points
double get_px() const
vpHomogeneousMatrix rMe
reference coordinates (manipulator base coordinates)
double computeStdDeviation_dist(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam)
double get_kud() const
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
void set_v(double v)
Definition: vpImagePoint.h:236
vpCameraParameters cam_dist
projection model with distortion
double get_kdu() const
int writeData(const char *filename)
vpHomogeneousMatrix eMc
Position of the camera in end-effector frame using camera parameters without distorsion.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:87
void computeStdDeviation(double &deviation, double &deviation_dist)
vpCameraParameters cam
projection model without distortion
Definition: vpCalibration.h:98
static int computeCalibrationMulti(vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam, double &globalReprojectionError, bool verbose=false)
void addPoint(const vpPoint &P)
Definition: vpPose.cpp:149
const char * getMessage() const
Definition: vpException.cpp:90
int displayData(vpImage< unsigned char > &I, vpColor color=vpColor::red, unsigned int thickness=1, int subsampling_factor=1)
double computeResidual(const vpHomogeneousMatrix &cMo) const
Compute and return the sum of squared residuals expressed in meter^2 for the pose matrix cMo...
Definition: vpPose.cpp:336
static int readGrid(const char *filename, unsigned int &n, std::list< double > &oX, std::list< double > &oY, std::list< double > &oZ, bool verbose=false)
void clearPoint()
Definition: vpPose.cpp:134