ViSP  2.10.0
vpCalibration.cpp
1 /****************************************************************************
2  *
3  * $Id: vpCalibration.cpp 5233 2015-01-30 13:50:39Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2014 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Camera calibration.
36  *
37  * Authors:
38  * Eric Marchand
39  * Francois Chaumette
40  * Anthony Saunier
41  *
42  *****************************************************************************/
43 
44 
50 #include <visp/vpCalibration.h>
51 #include <visp/vpDebug.h>
52 #include <visp/vpPose.h>
53 #include <visp/vpPixelMeterConversion.h>
54 
55 double vpCalibration::threshold = 1e-10f;
56 unsigned int vpCalibration::nbIterMax = 4000;
57 double vpCalibration::gain = 0.25;
62 {
63  npt = 0 ;
64 
65  residual = residual_dist = 1000.;
66 
67  LoX.clear() ;
68  LoY.clear() ;
69  LoZ.clear() ;
70  Lip.clear() ;
71 
72  return 0 ;
73 }
74 
79  : cMo(), cMo_dist(), cam(), cam_dist(), rMe(), eMc(), eMc_dist(),
80  npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.), residual_dist(1000.)
81 {
82  init() ;
83 }
88  : cMo(), cMo_dist(), cam(), cam_dist(), rMe(), eMc(), eMc_dist(),
89  npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.), residual_dist(1000.)
90 {
91  (*this) = c;
92 }
93 
94 
99 {
100  clearPoint() ;
101 }
102 
109 {
110  npt = twinCalibration.npt ;
111  LoX = twinCalibration.LoX ;
112  LoY = twinCalibration.LoY ;
113  LoZ = twinCalibration.LoZ ;
114  Lip = twinCalibration.Lip ;
115 
116  residual = twinCalibration.residual;
117  cMo = twinCalibration.cMo;
118  residual_dist = twinCalibration.residual_dist;
119  cMo_dist = twinCalibration.cMo_dist ;
120 
121  cam = twinCalibration.cam ;
122  cam_dist = twinCalibration.cam_dist ;
123 
124  rMe = twinCalibration.rMe;
125 
126  eMc = twinCalibration.eMc;
127  eMc_dist = twinCalibration.eMc_dist;
128 
129  return (*this);
130 }
131 
132 
137 {
138  LoX.clear() ;
139  LoY.clear() ;
140  LoZ.clear() ;
141  Lip.clear() ;
142  npt = 0 ;
143 
144  return 0 ;
145 }
146 
153 int vpCalibration::addPoint(double X, double Y, double Z, vpImagePoint &ip)
154 {
155  LoX.push_back(X);
156  LoY.push_back(Y);
157  LoZ.push_back(Z);
158 
159  Lip.push_back(ip);
160 
161  npt++ ;
162 
163  return 0 ;
164 }
165 
171 void vpCalibration::computePose(const vpCameraParameters &camera, vpHomogeneousMatrix &cMo_est)
172 {
173  // The vpPose class mainly contents a list of vpPoint (that is (X,Y,Z, x, y) )
174  vpPose pose ;
175  // the list of point is cleared (if that's not done before)
176  pose.clearPoint() ;
177  // we set the 3D points coordinates (in meter !) in the object/world frame
178  std::list<double>::const_iterator it_LoX = LoX.begin();
179  std::list<double>::const_iterator it_LoY = LoY.begin();
180  std::list<double>::const_iterator it_LoZ = LoZ.begin();
181  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
182 
183  for (unsigned int i =0 ; i < npt ; i++)
184  {
185  vpPoint P;
186  P.setWorldCoordinates(*it_LoX, *it_LoY, *it_LoZ);
187  double x=0,y=0 ;
188  vpPixelMeterConversion::convertPoint(camera, *it_Lip, x,y) ;
189  P.set_x(x) ;
190  P.set_y(y) ;
191 
192  pose.addPoint(P);
193  ++it_LoX;
194  ++it_LoY;
195  ++it_LoZ;
196  ++it_Lip;
197  }
198  vpHomogeneousMatrix cMo_dementhon; // computed pose with dementhon
199  vpHomogeneousMatrix cMo_lagrange; // computed pose with dementhon
200 
201  // compute the initial pose using Lagrange method followed by a non linear
202  // minimisation method
203  // Pose by Lagrange it provides an initialization of the pose
204  pose.computePose(vpPose::LAGRANGE, cMo_lagrange) ;
205  double residual_lagrange = pose.computeResidual(cMo_lagrange);
206 
207  // compute the initial pose using Dementhon method followed by a non linear
208  // minimisation method
209  // Pose by Dementhon it provides an initialization of the pose
210  pose.computePose(vpPose::DEMENTHON, cMo_dementhon) ;
211  double residual_dementhon = pose.computeResidual(cMo_dementhon);
212 
213  //we keep the better initialization
214  if (residual_lagrange < residual_dementhon)
215  cMo_est = cMo_lagrange;
216  else
217  cMo_est = cMo_dementhon;
218 
219  // the pose is now refined using the virtual visual servoing approach
220  // Warning: cMo needs to be initialized otherwise it may diverge
221  pose.computePose(vpPose::VIRTUAL_VS, cMo_est) ;
222 }
223 
232  const vpCameraParameters& camera)
233 {
234  double residual_ = 0 ;
235 
236  std::list<double>::const_iterator it_LoX = LoX.begin();
237  std::list<double>::const_iterator it_LoY = LoY.begin();
238  std::list<double>::const_iterator it_LoZ = LoZ.begin();
239  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
240 
241  double u0 = camera.get_u0() ;
242  double v0 = camera.get_v0() ;
243  double px = camera.get_px() ;
244  double py = camera.get_py() ;
245  vpImagePoint ip;
246 
247  for (unsigned int i =0 ; i < npt ; i++)
248  {
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  const vpCameraParameters& camera)
286 {
287  double residual_ = 0 ;
288 
289  std::list<double>::const_iterator it_LoX = LoX.begin();
290  std::list<double>::const_iterator it_LoY = LoY.begin();
291  std::list<double>::const_iterator it_LoZ = LoZ.begin();
292  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
293 
294  double u0 = camera.get_u0() ;
295  double v0 = camera.get_v0() ;
296  double px = camera.get_px() ;
297  double py = camera.get_py() ;
298  double kud = camera.get_kud() ;
299  double kdu = camera.get_kdu() ;
300 
301  double inv_px = 1/px;
302  double inv_py = 1/px;
303  vpImagePoint ip;
304 
305  for (unsigned int i =0 ; i < npt ; i++)
306  {
307  double oX = *it_LoX;
308  double oY = *it_LoY;
309  double oZ = *it_LoZ;
310 
311  double cX = oX*cMo_est[0][0]+oY*cMo_est[0][1]+oZ*cMo_est[0][2] + cMo_est[0][3];
312  double cY = oX*cMo_est[1][0]+oY*cMo_est[1][1]+oZ*cMo_est[1][2] + cMo_est[1][3];
313  double cZ = oX*cMo_est[2][0]+oY*cMo_est[2][1]+oZ*cMo_est[2][2] + cMo_est[2][3];
314 
315  double x = cX/cZ ;
316  double y = cY/cZ ;
317 
318  ip = *it_Lip;
319  double u = ip.get_u() ;
320  double v = ip.get_v() ;
321 
322  double r2ud = 1+kud*(vpMath::sqr(x)+vpMath::sqr(y)) ;
323 
324  double xp = u0 + x*px*r2ud;
325  double yp = v0 + y*py*r2ud;
326 
327  residual_ += (vpMath::sqr(xp-u) + vpMath::sqr(yp-v)) ;
328 
329  double r2du = (vpMath::sqr((u-u0)*inv_px)+vpMath::sqr((v-v0)*inv_py)) ;
330 
331  xp = u0 + x*px - kdu*(u-u0)*r2du;
332  yp = v0 + y*py - kdu*(v-v0)*r2du;
333 
334  residual_ += (vpMath::sqr(xp-u) + vpMath::sqr(yp-v)) ;
335  ++it_LoX;
336  ++it_LoY;
337  ++it_LoZ;
338  ++it_Lip;
339  }
340  residual_ /=2;
341 
342  this->residual_dist = residual_;
343  return sqrt(residual_/npt) ;
344 }
345 
352 void
353  vpCalibration::computeStdDeviation(double &deviation,double &deviation_dist)
354 {
355  deviation = computeStdDeviation(cMo,cam);
356  deviation_dist = computeStdDeviation_dist(cMo_dist,cam_dist);
357 }
358 
359 
372  vpHomogeneousMatrix &cMo_est,
373  vpCameraParameters &cam_est,
374  bool verbose)
375 {
376  try{
377  computePose(cam_est,cMo_est);
378  switch (method)
379  {
380  case CALIB_LAGRANGE :
382  {
383  calibLagrange(cam_est, cMo_est);
384  }
385  break;
386  case CALIB_VIRTUAL_VS:
389  default:
390  break;
391  }
392 
393  switch (method)
394  {
395  case CALIB_VIRTUAL_VS:
399  {
400  if (verbose){std::cout << "start calibration without distortion"<< std::endl;}
401  calibVVS(cam_est, cMo_est, verbose);
402  }
403  break ;
404  case CALIB_LAGRANGE:
405  default:
406  break;
407  }
408  this->cMo = cMo_est;
409  this->cMo_dist = cMo_est;
410 
411  //Print camera parameters
412  if(verbose){
413  // std::cout << "Camera parameters without distortion :" << std::endl;
414  cam_est.printParameters();
415  }
416 
417  this->cam = cam_est;
418 
419  switch (method)
420  {
423  {
424  if (verbose){std::cout << "start calibration with distortion"<< std::endl;}
425  calibVVSWithDistortion(cam_est, cMo_est, verbose);
426  }
427  break ;
428  case CALIB_LAGRANGE:
429  case CALIB_VIRTUAL_VS:
431  default:
432  break;
433  }
434  //Print camera parameters
435  if(verbose){
436  // std::cout << "Camera parameters without distortion :" << std::endl;
437  this->cam.printParameters();
438  // std::cout << "Camera parameters with distortion :" << std::endl;
439  cam_est.printParameters();
440  }
441 
442  this->cam_dist = cam_est ;
443 
444  this->cMo_dist = cMo_est;
445  return 0 ;
446  }
447  catch(...){
448  throw;
449  }
450 }
451 
465  std::vector<vpCalibration> &table_cal,
466  vpCameraParameters& cam_est,
467  double &globalReprojectionError,
468  bool verbose)
469 {
470  try{
471  unsigned int nbPose = (unsigned int) table_cal.size();
472  for(unsigned int i=0;i<nbPose;i++){
473  if(table_cal[i].get_npt()>3)
474  table_cal[i].computePose(cam_est,table_cal[i].cMo);
475  }
476  switch (method) {
477  case CALIB_LAGRANGE : {
478  if(nbPose > 1){
479  std::cout << "this calibration method is not available in" << std::endl
480  << "vpCalibration::computeCalibrationMulti()" << std::endl;
481  return -1 ;
482  }
483  else {
484  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
485  table_cal[0].cam = cam_est ;
486  table_cal[0].cam_dist = cam_est ;
487  table_cal[0].cMo_dist = table_cal[0].cMo ;
488  }
489  break;
490  }
493  if(nbPose > 1){
494  std::cout << "this calibration method is not available in" << std::endl
495  << "vpCalibration::computeCalibrationMulti()" << std::endl
496  << "with several images." << std::endl;
497  return -1 ;
498  }
499  else {
500  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
501  table_cal[0].cam = cam_est ;
502  table_cal[0].cam_dist = cam_est ;
503  table_cal[0].cMo_dist = table_cal[0].cMo ;
504  }
505  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
506  break ;
507  }
508  case CALIB_VIRTUAL_VS:
509  case CALIB_VIRTUAL_VS_DIST: {
510  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
511  break ;
512  }
513  }
514  //Print camera parameters
515  if(verbose){
516  // std::cout << "Camera parameters without distortion :" << std::endl;
517  cam_est.printParameters();
518  }
519 
520  switch (method)
521  {
522  case CALIB_LAGRANGE :
524  case CALIB_VIRTUAL_VS:
525  verbose = false ;
526  break;
529  {
530  if(verbose)
531  std::cout << "Compute camera parameters with distortion"<<std::endl;
532 
533  calibVVSWithDistortionMulti(table_cal, cam_est, globalReprojectionError, verbose);
534  }
535  break ;
536  }
537  //Print camera parameters
538  if(verbose){
539  // std::cout << "Camera parameters without distortion :" << std::endl;
540  table_cal[0].cam.printParameters();
541  // std::cout << "Camera parameters with distortion:" << std::endl;
542  cam_est.printParameters();
543  std::cout<<std::endl;
544  }
545  return 0 ;
546  }
547  catch(...){ throw; }
548 }
549 
565 int vpCalibration::computeCalibrationTsai(std::vector<vpCalibration> &table_cal,
566  vpHomogeneousMatrix& eMc,
567  vpHomogeneousMatrix& eMc_dist)
568 {
569  try{
570  unsigned int nbPose = (unsigned int)table_cal.size();
571  if (nbPose > 2){
572  std::vector<vpHomogeneousMatrix> table_cMo(nbPose);
573  std::vector<vpHomogeneousMatrix> table_cMo_dist(nbPose);
574  std::vector<vpHomogeneousMatrix> table_rMe(nbPose);
575 
576  for(unsigned int i=0;i<nbPose;i++){
577  table_cMo[i] = table_cal[i].cMo;
578  table_cMo_dist[i] = table_cal[i].cMo_dist;
579  table_rMe[i] = table_cal[i].rMe;
580  }
581  calibrationTsai(table_cMo, table_rMe, eMc);
582  calibrationTsai(table_cMo_dist, table_rMe, eMc_dist);
583 
584  return 0;
585  }
586  else{
587  vpERROR_TRACE("Three images are needed to compute Tsai calibration !\n");
588  return -1;
589  }
590  }
591  catch(...){
592  throw;
593  }
594 }
595 
596 
604 int vpCalibration::writeData(const char *filename)
605 {
606  std::ofstream f(filename) ;
607  vpImagePoint ip;
608 
609  std::list<double>::const_iterator it_LoX = LoX.begin();
610  std::list<double>::const_iterator it_LoY = LoY.begin();
611  std::list<double>::const_iterator it_LoZ = LoZ.begin();
612  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
613 
614  f.precision(10);
615  f.setf(std::ios::fixed,std::ios::floatfield);
616  f << LoX.size() << std::endl ;
617 
618  for (unsigned int i =0 ; i < LoX.size() ; i++)
619  {
620 
621  double oX = *it_LoX;
622  double oY = *it_LoY;
623  double oZ = *it_LoZ;
624 
625  ip = *it_Lip;
626  double u = ip.get_u() ;
627  double v = ip.get_v() ;
628 
629  f << oX <<" " << oY << " " << oZ << " " << u << " " << v <<std::endl ;
630 
631  ++it_LoX;
632  ++it_LoY;
633  ++it_LoZ;
634  ++it_Lip;
635 
636  }
637 
638  f.close() ;
639  return 0 ;
640 }
641 
648 int vpCalibration::readData(const char* filename)
649 {
650  vpImagePoint ip;
651  std::ifstream f;
652  f.open(filename);
653  if (! f.fail()){
654  unsigned int n ;
655  f >> n ;
656  std::cout << "There are "<< n <<" point on the calibration grid " << std::endl ;
657 
658  clearPoint() ;
659 
660  if (n > 100000)
661  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
662 
663  for (unsigned int i=0 ; i < n ; i++)
664  {
665  double x, y, z, u, v ;
666  f >> x >> y >> z >> u >> v ;
667  std::cout << x <<" "<<y <<" "<<z<<" "<<u<<" "<<v <<std::endl ;
668  ip.set_u( u );
669  ip.set_v( v );
670  addPoint(x, y, z, ip) ;
671  }
672 
673  f.close() ;
674  return 0 ;
675  }
676  else{
677  return -1;
678  }
679 }
696 int vpCalibration::readGrid(const char* filename, unsigned int &n,
697  std::list<double> &oX, std::list<double> &oY, std::list<double> &oZ, bool verbose)
698 {
699  try{
700  std::ifstream f;
701  f.open(filename);
702  if (! f.fail()){
703 
704  f >> n ;
705  if(verbose)
706  std::cout << "There are "<< n <<" points on the calibration grid " << std::endl ;
707  int no_pt;
708  double x,y,z;
709 
710  // clear the list
711  oX.clear();
712  oY.clear();
713  oZ.clear();
714 
715  if (n > 100000)
716  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
717 
718  for (unsigned int i=0 ; i < n ; i++)
719  {
720  f >> no_pt >> x >> y >> z ;
721  if(verbose){
722  std::cout << no_pt <<std::endl ;
723  std::cout << x <<" "<< y <<" "<< z <<std::endl ;
724  }
725  oX.push_back(x) ;
726  oY.push_back(y) ;
727  oZ.push_back(z) ;
728  }
729 
730  f.close() ;
731  }
732  else{
733  return -1;
734  }
735  }
736  catch(...){return -1;}
737  return 0 ;
738 }
739 
751  unsigned int thickness, int subsampling_factor)
752 {
753 
754  for (std::list<vpImagePoint>::const_iterator it = Lip.begin(); it != Lip.end(); ++ it) {
755  vpImagePoint ip = *it;
756  if (subsampling_factor > 1.) {
757  ip.set_u( ip.get_u() / subsampling_factor);
758  ip.set_v( ip.get_v() / subsampling_factor);
759  }
760  vpDisplay::displayCross(I, ip, 12, color, thickness) ;
761  }
762  return 0 ;
763 }
764 
776  unsigned int thickness, int subsampling_factor)
777 {
778  double u0_dist = cam_dist.get_u0() / subsampling_factor;
779  double v0_dist = cam_dist.get_v0() / subsampling_factor;
780  double px_dist = cam_dist.get_px() / subsampling_factor;
781  double py_dist = cam_dist.get_py() / subsampling_factor;
782  double kud_dist = cam_dist.get_kud() ;
783  // double kdu_dist = cam_dist.get_kdu() ;
784 
785  // double u0 = cam.get_u0() ;
786  // double v0 = cam.get_v0() ;
787  // double px = cam.get_px() ;
788  // double py = cam.get_py() ;
789 
790  std::list<double>::const_iterator it_LoX = LoX.begin();
791  std::list<double>::const_iterator it_LoY = LoY.begin();
792  std::list<double>::const_iterator it_LoZ = LoZ.begin();
793 
794  for (unsigned int i =0 ; i < npt ; i++)
795  {
796  double oX = *it_LoX;
797  double oY = *it_LoY;
798  double oZ = *it_LoZ;
799 
800  double cX = oX*cMo[0][0]+oY*cMo[0][1]+oZ*cMo[0][2] + cMo[0][3];
801  double cY = oX*cMo[1][0]+oY*cMo[1][1]+oZ*cMo[1][2] + cMo[1][3];
802  double cZ = oX*cMo[2][0]+oY*cMo[2][1]+oZ*cMo[2][2] + cMo[2][3];
803 
804  double x = cX/cZ ;
805  double y = cY/cZ ;
806 
807  // double xp = u0 + x*px ;
808  // double yp = v0 + y*py ;
809 
810  // vpDisplay::displayCross(I,(int)vpMath::round(yp), (int)vpMath::round(xp),
811  // 5,col) ;
812 
813  cX = oX*cMo_dist[0][0]+oY*cMo_dist[0][1]+oZ*cMo_dist[0][2]+cMo_dist[0][3];
814  cY = oX*cMo_dist[1][0]+oY*cMo_dist[1][1]+oZ*cMo_dist[1][2]+cMo_dist[1][3];
815  cZ = oX*cMo_dist[2][0]+oY*cMo_dist[2][1]+oZ*cMo_dist[2][2]+cMo_dist[2][3];
816 
817  x = cX/cZ ;
818  y = cY/cZ ;
819 
820  double r2 = 1+kud_dist*(vpMath::sqr(x)+vpMath::sqr(y)) ;
821 
822  vpImagePoint ip;
823  ip.set_u( u0_dist + x*px_dist*r2 );
824  ip.set_v( v0_dist + y*py_dist*r2 );
825 
826  vpDisplay::displayCross(I, ip, 6, color, thickness) ;
828 
829  // std::cout << oX << " " << oY << " " <<oZ << std::endl ;
830  // I.getClick() ;
831  ++it_LoX;
832  ++it_LoY;
833  ++it_LoZ;
834  }
835  return 0;
836 }
837 
838 #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS
839 
856  unsigned int nbPose,
857  vpCalibration table_cal[],
858  vpCameraParameters& cam_est,
859  bool verbose)
860 {
861  try{
862  for(unsigned int i=0;i<nbPose;i++){
863  if(table_cal[i].get_npt()>3)
864  table_cal[i].computePose(cam_est,table_cal[i].cMo);
865  }
866  switch (method) {
867  case CALIB_LAGRANGE : {
868  if(nbPose > 1){
869  std::cout << "this calibration method is not available in" << std::endl
870  << "vpCalibration::computeCalibrationMulti()" << std::endl;
871  return -1 ;
872  }
873  else {
874  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
875  table_cal[0].cam = cam_est ;
876  table_cal[0].cam_dist = cam_est ;
877  table_cal[0].cMo_dist = table_cal[0].cMo ;
878  }
879  break;
880  }
883  if(nbPose > 1){
884  std::cout << "this calibration method is not available in" << std::endl
885  << "vpCalibration::computeCalibrationMulti()" << std::endl
886  << "with several images." << std::endl;
887  return -1 ;
888  }
889  else {
890  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
891  table_cal[0].cam = cam_est ;
892  table_cal[0].cam_dist = cam_est ;
893  table_cal[0].cMo_dist = table_cal[0].cMo ;
894  }
895  calibVVSMulti(nbPose, table_cal, cam_est, verbose);
896  break ;
897  }
898  case CALIB_VIRTUAL_VS:
899  case CALIB_VIRTUAL_VS_DIST: {
900  calibVVSMulti(nbPose, table_cal, cam_est, verbose);
901  break ;
902  }
903  }
904  //Print camera parameters
905  if(verbose){
906  // std::cout << "Camera parameters without distortion :" << std::endl;
907  cam_est.printParameters();
908  }
909 
910  switch (method)
911  {
912  case CALIB_LAGRANGE :
914  case CALIB_VIRTUAL_VS:
915  verbose = false ;
916  break;
919  {
920  if(verbose)
921  std::cout << "Compute camera parameters with distortion"<<std::endl;
922 
923  calibVVSWithDistortionMulti(nbPose, table_cal, cam_est, verbose);
924  }
925  break ;
926  }
927  //Print camera parameters
928  if(verbose){
929  // std::cout << "Camera parameters without distortion :" << std::endl;
930  table_cal[0].cam.printParameters();
931  // std::cout << "Camera parameters with distortion:" << std::endl;
932  cam_est.printParameters();
933  std::cout<<std::endl;
934  }
935  return 0 ;
936  }
937  catch(...){ throw; }
938 }
939 
960  vpCalibration table_cal[],
961  vpHomogeneousMatrix& eMc,
962  vpHomogeneousMatrix& eMc_dist)
963 {
964  try{
965  if (nbPose > 2){
966  vpHomogeneousMatrix* table_cMo = new vpHomogeneousMatrix[nbPose];
967  vpHomogeneousMatrix* table_cMo_dist = new vpHomogeneousMatrix[nbPose];
968  vpHomogeneousMatrix* table_rMe = new vpHomogeneousMatrix[nbPose];
969 
970  for(unsigned int i=0;i<nbPose;i++){
971  table_cMo[i] = table_cal[i].cMo;
972  table_cMo_dist[i] = table_cal[i].cMo_dist;
973  table_rMe[i] = table_cal[i].rMe;
974  }
975  calibrationTsai(nbPose,table_cMo,table_rMe,eMc);
976  calibrationTsai(nbPose,table_cMo_dist,table_rMe,eMc_dist);
977 
978  delete [] table_cMo;
979  delete [] table_cMo_dist;
980  delete [] table_rMe;
981 
982  return 0;
983  }
984  else{
985  vpERROR_TRACE("Three images are needed to compute Tsai calibration !\n");
986  return -1;
987  }
988  }
989  catch(...){
990  throw;
991  }
992 }
993 
1013 int vpCalibration::readGrid(const char* filename,unsigned int &n,
1014  vpList<double> &oX,vpList<double> &oY,vpList<double> &oZ, bool verbose)
1015 {
1016  try{
1017  std::ifstream f;
1018  f.open(filename);
1019  if (! f.fail()){
1020 
1021  f >> n ;
1022  if(verbose)
1023  std::cout << "There are "<< n <<" points on the calibration grid " << std::endl ;
1024  int no_pt;
1025  double x,y,z;
1026 
1027  oX.front();
1028  oY.front();
1029  oZ.front();
1030 
1031  if (n > 100000)
1032  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
1033 
1034  for (unsigned int i=0 ; i < n ; i++)
1035  {
1036  f >> no_pt >> x >> y >> z ;
1037  if(verbose){
1038  std::cout << no_pt <<std::endl ;
1039  std::cout << x <<" "<< y <<" "<< z <<std::endl ;
1040  }
1041  oX.addRight(x) ;
1042  oY.addRight(y) ;
1043  oZ.addRight(z) ;
1044  }
1045 
1046  f.close() ;
1047  }
1048  else{
1049  return -1;
1050  }
1051  }
1052  catch(...){return -1;}
1053  return 0 ;
1054 }
1055 
1056 #endif // VISP_BUILD_DEPRECATED_FUNCTIONS
double get_v() const
Definition: vpImagePoint.h:264
double get_u0() const
int computeCalibration(vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false)
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:395
Provide simple list management.
Definition: vpList.h:113
int readData(const char *filename)
Class to define colors available for display functionnalities.
Definition: vpColor.h:125
double get_u() const
Definition: vpImagePoint.h:253
error that can be emited by ViSP classes.
Definition: vpException.h:76
int addPoint(double X, double Y, double Z, vpImagePoint &ip)
void set_x(const double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.h:194
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Point coordinates conversion from pixel coordinates to normalized coordinates in meter...
double get_py() const
Tools for perspective camera calibration.
Definition: vpCalibration.h:78
virtual ~vpCalibration()
vpHomogeneousMatrix cMo
(as a 3x4 matrix [R T])
Definition: vpCalibration.h:92
Class that defines what is a point.
Definition: vpPoint.h:65
vpCalibration & operator=(const vpCalibration &twinCalibration)
int clearPoint()
Suppress all the point in the array of point.
double get_v0() const
void set_u(const double u)
Definition: vpImagePoint.h:217
static double sqr(double x)
Definition: vpMath.h:106
void front(void)
Position the current element on the first element of the list.
Definition: vpList.h:384
bool computePose(vpPoseMethodType methode, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
compute the pose for a given method
Definition: vpPose.cpp:386
int displayGrid(vpImage< unsigned char > &I, vpColor color=vpColor::yellow, unsigned int thickness=1, int subsampling_factor=1)
vpHomogeneousMatrix cMo_dist
Definition: vpCalibration.h:94
virtual void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)=0
void set_v(const double v)
Definition: vpImagePoint.h:228
Class used for pose computation from N points (pose from point only).
Definition: vpPose.h:78
Generic class defining intrinsic camera parameters.
void addRight(const type &el)
add a new element in the list, at the right of the current one
Definition: vpList.h:478
vpHomogeneousMatrix eMc_dist
void set_y(const double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.h:196
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)
static void calibrationTsai(std::vector< vpHomogeneousMatrix > &cMo, std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc)
calibration method of effector-camera from R. Tsai and R. Lorenz .
double get_kud() const
vpCameraParameters cam_dist
projection model with distortion
Definition: vpCalibration.h:99
double get_kdu() const
int writeData(const char *filename)
vpHomogeneousMatrix eMc
position of the camera in relation to the effector
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:93
static int computeCalibrationTsai(std::vector< vpCalibration > &table_cal, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &eMc_dist)
Compute the multi-image calibration of effector-camera from R. Tsai and R. Lenz . ...
void computeStdDeviation(double &deviation, double &deviation_dist)
vpCameraParameters cam
projection model without distortion
Definition: vpCalibration.h:97
static int computeCalibrationMulti(vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam, double &globalReprojectionError, bool verbose=false)
void addPoint(const vpPoint &P)
Add a new point in this array.
Definition: vpPose.cpp:155
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 residual expressed in meter for the pose matrix 'cMo'.
Definition: vpPose.cpp:344
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 setWorldCoordinates(const double ox, const double oy, const double oz)
Set the point world coordinates. We mean here the coordinates of the point in the object frame...
Definition: vpPoint.cpp:74
void clearPoint()
suppress all the point in the array of point
Definition: vpPose.cpp:133