Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpCalibration.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Camera calibration.
32  *
33  * Authors:
34  * Eric Marchand
35  * Francois Chaumette
36  * Anthony Saunier
37  *
38  *****************************************************************************/
39 
40 
46 #include <visp3/vision/vpCalibration.h>
47 #include <visp3/core/vpDebug.h>
48 #include <visp3/vision/vpPose.h>
49 #include <visp3/core/vpPixelMeterConversion.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(),
76  npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.), residual_dist(1000.)
77 {
78  init() ;
79 }
84  : cMo(), cMo_dist(), cam(), cam_dist(), rMe(), eMc(), eMc_dist(),
85  npt(0), LoX(), LoY(), LoZ(), Lip(), residual(1000.), residual_dist(1000.)
86 {
87  (*this) = c;
88 }
89 
90 
95 {
96  clearPoint() ;
97 }
98 
105 {
106  npt = twinCalibration.npt ;
107  LoX = twinCalibration.LoX ;
108  LoY = twinCalibration.LoY ;
109  LoZ = twinCalibration.LoZ ;
110  Lip = twinCalibration.Lip ;
111 
112  residual = twinCalibration.residual;
113  cMo = twinCalibration.cMo;
114  residual_dist = twinCalibration.residual_dist;
115  cMo_dist = twinCalibration.cMo_dist ;
116 
117  cam = twinCalibration.cam ;
118  cam_dist = twinCalibration.cam_dist ;
119 
120  rMe = twinCalibration.rMe;
121 
122  eMc = twinCalibration.eMc;
123  eMc_dist = twinCalibration.eMc_dist;
124 
125  return (*this);
126 }
127 
128 
133 {
134  LoX.clear() ;
135  LoY.clear() ;
136  LoZ.clear() ;
137  Lip.clear() ;
138  npt = 0 ;
139 
140  return 0 ;
141 }
142 
149 int vpCalibration::addPoint(double X, double Y, double Z, vpImagePoint &ip)
150 {
151  LoX.push_back(X);
152  LoY.push_back(Y);
153  LoZ.push_back(Z);
154 
155  Lip.push_back(ip);
156 
157  npt++ ;
158 
159  return 0 ;
160 }
161 
167 void vpCalibration::computePose(const vpCameraParameters &camera, vpHomogeneousMatrix &cMo_est)
168 {
169  // The vpPose class mainly contents a list of vpPoint (that is (X,Y,Z, x, y) )
170  vpPose pose ;
171  // the list of point is cleared (if that's not done before)
172  pose.clearPoint() ;
173  // we set the 3D points coordinates (in meter !) in the object/world frame
174  std::list<double>::const_iterator it_LoX = LoX.begin();
175  std::list<double>::const_iterator it_LoY = LoY.begin();
176  std::list<double>::const_iterator it_LoZ = LoZ.begin();
177  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
178 
179  for (unsigned int i =0 ; i < npt ; i++)
180  {
181  vpPoint P(*it_LoX, *it_LoY, *it_LoZ);
182  double x=0,y=0 ;
183  vpPixelMeterConversion::convertPoint(camera, *it_Lip, x,y) ;
184  P.set_x(x) ;
185  P.set_y(y) ;
186 
187  pose.addPoint(P);
188  ++it_LoX;
189  ++it_LoY;
190  ++it_LoZ;
191  ++it_Lip;
192  }
193  vpHomogeneousMatrix cMo_dementhon; // computed pose with dementhon
194  vpHomogeneousMatrix cMo_lagrange; // computed pose with dementhon
195 
196  // compute the initial pose using Lagrange method followed by a non linear
197  // minimisation method
198  // Pose by Lagrange it provides an initialization of the pose
199  pose.computePose(vpPose::LAGRANGE, cMo_lagrange) ;
200  double residual_lagrange = pose.computeResidual(cMo_lagrange);
201 
202  // compute the initial pose using Dementhon method followed by a non linear
203  // minimisation method
204  // Pose by Dementhon it provides an initialization of the pose
205  pose.computePose(vpPose::DEMENTHON, cMo_dementhon) ;
206  double residual_dementhon = pose.computeResidual(cMo_dementhon);
207 
208  //we keep the better initialization
209  if (residual_lagrange < residual_dementhon)
210  cMo_est = cMo_lagrange;
211  else
212  cMo_est = cMo_dementhon;
213 
214  // the pose is now refined using the virtual visual servoing approach
215  // Warning: cMo needs to be initialized otherwise it may diverge
216  pose.computePose(vpPose::VIRTUAL_VS, cMo_est) ;
217 }
218 
227  const vpCameraParameters& camera)
228 {
229  double residual_ = 0 ;
230 
231  std::list<double>::const_iterator it_LoX = LoX.begin();
232  std::list<double>::const_iterator it_LoY = LoY.begin();
233  std::list<double>::const_iterator it_LoZ = LoZ.begin();
234  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
235 
236  double u0 = camera.get_u0() ;
237  double v0 = camera.get_v0() ;
238  double px = camera.get_px() ;
239  double py = camera.get_py() ;
240  vpImagePoint ip;
241 
242  for (unsigned int i =0 ; i < npt ; i++)
243  {
244  double oX = *it_LoX;
245  double oY = *it_LoY;
246  double oZ = *it_LoZ;
247 
248  double cX = oX*cMo_est[0][0]+oY*cMo_est[0][1]+oZ*cMo_est[0][2] + cMo_est[0][3];
249  double cY = oX*cMo_est[1][0]+oY*cMo_est[1][1]+oZ*cMo_est[1][2] + cMo_est[1][3];
250  double cZ = oX*cMo_est[2][0]+oY*cMo_est[2][1]+oZ*cMo_est[2][2] + cMo_est[2][3];
251 
252  double x = cX/cZ ;
253  double y = cY/cZ ;
254 
255  ip = *it_Lip;
256  double u = ip.get_u() ;
257  double v = ip.get_v() ;
258 
259  double xp = u0 + x*px;
260  double yp = v0 + y*py;
261 
262  residual_ += (vpMath::sqr(xp-u) + vpMath::sqr(yp-v)) ;
263 
264  ++it_LoX;
265  ++it_LoY;
266  ++it_LoZ;
267  ++it_Lip;
268  }
269  this->residual = residual_ ;
270  return sqrt(residual_/npt) ;
271 }
280  const vpCameraParameters& camera)
281 {
282  double residual_ = 0 ;
283 
284  std::list<double>::const_iterator it_LoX = LoX.begin();
285  std::list<double>::const_iterator it_LoY = LoY.begin();
286  std::list<double>::const_iterator it_LoZ = LoZ.begin();
287  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
288 
289  double u0 = camera.get_u0() ;
290  double v0 = camera.get_v0() ;
291  double px = camera.get_px() ;
292  double py = camera.get_py() ;
293  double kud = camera.get_kud() ;
294  double kdu = camera.get_kdu() ;
295 
296  double inv_px = 1/px;
297  double inv_py = 1/px;
298  vpImagePoint ip;
299 
300  for (unsigned int i =0 ; i < npt ; i++)
301  {
302  double oX = *it_LoX;
303  double oY = *it_LoY;
304  double oZ = *it_LoZ;
305 
306  double cX = oX*cMo_est[0][0]+oY*cMo_est[0][1]+oZ*cMo_est[0][2] + cMo_est[0][3];
307  double cY = oX*cMo_est[1][0]+oY*cMo_est[1][1]+oZ*cMo_est[1][2] + cMo_est[1][3];
308  double cZ = oX*cMo_est[2][0]+oY*cMo_est[2][1]+oZ*cMo_est[2][2] + cMo_est[2][3];
309 
310  double x = cX/cZ ;
311  double y = cY/cZ ;
312 
313  ip = *it_Lip;
314  double u = ip.get_u() ;
315  double v = ip.get_v() ;
316 
317  double r2ud = 1+kud*(vpMath::sqr(x)+vpMath::sqr(y)) ;
318 
319  double xp = u0 + x*px*r2ud;
320  double yp = v0 + y*py*r2ud;
321 
322  residual_ += (vpMath::sqr(xp-u) + vpMath::sqr(yp-v)) ;
323 
324  double r2du = (vpMath::sqr((u-u0)*inv_px)+vpMath::sqr((v-v0)*inv_py)) ;
325 
326  xp = u0 + x*px - kdu*(u-u0)*r2du;
327  yp = v0 + y*py - kdu*(v-v0)*r2du;
328 
329  residual_ += (vpMath::sqr(xp-u) + vpMath::sqr(yp-v)) ;
330  ++it_LoX;
331  ++it_LoY;
332  ++it_LoZ;
333  ++it_Lip;
334  }
335  residual_ /=2;
336 
337  this->residual_dist = residual_;
338  return sqrt(residual_/npt) ;
339 }
340 
347 void
348  vpCalibration::computeStdDeviation(double &deviation,double &deviation_dist)
349 {
350  deviation = computeStdDeviation(cMo,cam);
351  deviation_dist = computeStdDeviation_dist(cMo_dist,cam_dist);
352 }
353 
354 
367  vpHomogeneousMatrix &cMo_est,
368  vpCameraParameters &cam_est,
369  bool verbose)
370 {
371  try{
372  computePose(cam_est,cMo_est);
373  switch (method)
374  {
375  case CALIB_LAGRANGE :
377  {
378  calibLagrange(cam_est, cMo_est);
379  }
380  break;
381  case CALIB_VIRTUAL_VS:
384  default:
385  break;
386  }
387 
388  switch (method)
389  {
390  case CALIB_VIRTUAL_VS:
394  {
395  if (verbose){std::cout << "start calibration without distortion"<< std::endl;}
396  calibVVS(cam_est, cMo_est, verbose);
397  }
398  break ;
399  case CALIB_LAGRANGE:
400  default:
401  break;
402  }
403  this->cMo = cMo_est;
404  this->cMo_dist = cMo_est;
405 
406  //Print camera parameters
407  if(verbose){
408  // std::cout << "Camera parameters without distortion :" << std::endl;
409  cam_est.printParameters();
410  }
411 
412  this->cam = cam_est;
413 
414  switch (method)
415  {
418  {
419  if (verbose){std::cout << "start calibration with distortion"<< std::endl;}
420  calibVVSWithDistortion(cam_est, cMo_est, verbose);
421  }
422  break ;
423  case CALIB_LAGRANGE:
424  case CALIB_VIRTUAL_VS:
426  default:
427  break;
428  }
429  //Print camera parameters
430  if(verbose){
431  // std::cout << "Camera parameters without distortion :" << std::endl;
432  this->cam.printParameters();
433  // std::cout << "Camera parameters with distortion :" << std::endl;
434  cam_est.printParameters();
435  }
436 
437  this->cam_dist = cam_est ;
438 
439  this->cMo_dist = cMo_est;
440  return 0 ;
441  }
442  catch(...){
443  throw;
444  }
445 }
446 
460  std::vector<vpCalibration> &table_cal,
461  vpCameraParameters& cam_est,
462  double &globalReprojectionError,
463  bool verbose)
464 {
465  try{
466  unsigned int nbPose = (unsigned int) table_cal.size();
467  for(unsigned int i=0;i<nbPose;i++){
468  if(table_cal[i].get_npt()>3)
469  table_cal[i].computePose(cam_est,table_cal[i].cMo);
470  }
471  switch (method) {
472  case CALIB_LAGRANGE : {
473  if(nbPose > 1){
474  std::cout << "this calibration method is not available in" << std::endl
475  << "vpCalibration::computeCalibrationMulti()" << std::endl;
476  return -1 ;
477  }
478  else {
479  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
480  table_cal[0].cam = cam_est ;
481  table_cal[0].cam_dist = cam_est ;
482  table_cal[0].cMo_dist = table_cal[0].cMo ;
483  }
484  break;
485  }
488  if(nbPose > 1){
489  std::cout << "this calibration method is not available in" << std::endl
490  << "vpCalibration::computeCalibrationMulti()" << std::endl
491  << "with several images." << std::endl;
492  return -1 ;
493  }
494  else {
495  table_cal[0].calibLagrange(cam_est,table_cal[0].cMo);
496  table_cal[0].cam = cam_est ;
497  table_cal[0].cam_dist = cam_est ;
498  table_cal[0].cMo_dist = table_cal[0].cMo ;
499  }
500  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
501  break ;
502  }
503  case CALIB_VIRTUAL_VS:
504  case CALIB_VIRTUAL_VS_DIST: {
505  calibVVSMulti(table_cal, cam_est, globalReprojectionError, verbose);
506  break ;
507  }
508  }
509  //Print camera parameters
510  if(verbose){
511  // std::cout << "Camera parameters without distortion :" << std::endl;
512  cam_est.printParameters();
513  }
514 
515  switch (method)
516  {
517  case CALIB_LAGRANGE :
519  case CALIB_VIRTUAL_VS:
520  verbose = false ;
521  break;
524  {
525  if(verbose)
526  std::cout << "Compute camera parameters with distortion"<<std::endl;
527 
528  calibVVSWithDistortionMulti(table_cal, cam_est, globalReprojectionError, verbose);
529  }
530  break ;
531  }
532  //Print camera parameters
533  if(verbose){
534  // std::cout << "Camera parameters without distortion :" << std::endl;
535  table_cal[0].cam.printParameters();
536  // std::cout << "Camera parameters with distortion:" << std::endl;
537  cam_est.printParameters();
538  std::cout<<std::endl;
539  }
540  return 0 ;
541  }
542  catch(...){ throw; }
543 }
544 
560 int vpCalibration::computeCalibrationTsai(std::vector<vpCalibration> &table_cal,
561  vpHomogeneousMatrix& eMc,
562  vpHomogeneousMatrix& eMc_dist)
563 {
564  try{
565  unsigned int nbPose = (unsigned int)table_cal.size();
566  if (nbPose > 2){
567  std::vector<vpHomogeneousMatrix> table_cMo(nbPose);
568  std::vector<vpHomogeneousMatrix> table_cMo_dist(nbPose);
569  std::vector<vpHomogeneousMatrix> table_rMe(nbPose);
570 
571  for(unsigned int i=0;i<nbPose;i++){
572  table_cMo[i] = table_cal[i].cMo;
573  table_cMo_dist[i] = table_cal[i].cMo_dist;
574  table_rMe[i] = table_cal[i].rMe;
575  }
576  calibrationTsai(table_cMo, table_rMe, eMc);
577  calibrationTsai(table_cMo_dist, table_rMe, eMc_dist);
578 
579  return 0;
580  }
581  else{
582  vpERROR_TRACE("Three images are needed to compute Tsai calibration !\n");
583  return -1;
584  }
585  }
586  catch(...){
587  throw;
588  }
589 }
590 
591 
599 int vpCalibration::writeData(const char *filename)
600 {
601  std::ofstream f(filename) ;
602  vpImagePoint ip;
603 
604  std::list<double>::const_iterator it_LoX = LoX.begin();
605  std::list<double>::const_iterator it_LoY = LoY.begin();
606  std::list<double>::const_iterator it_LoZ = LoZ.begin();
607  std::list<vpImagePoint>::const_iterator it_Lip = Lip.begin();
608 
609  f.precision(10);
610  f.setf(std::ios::fixed,std::ios::floatfield);
611  f << LoX.size() << std::endl ;
612 
613  for (unsigned int i =0 ; i < LoX.size() ; i++)
614  {
615 
616  double oX = *it_LoX;
617  double oY = *it_LoY;
618  double oZ = *it_LoZ;
619 
620  ip = *it_Lip;
621  double u = ip.get_u() ;
622  double v = ip.get_v() ;
623 
624  f << oX <<" " << oY << " " << oZ << " " << u << " " << v <<std::endl ;
625 
626  ++it_LoX;
627  ++it_LoY;
628  ++it_LoZ;
629  ++it_Lip;
630 
631  }
632 
633  f.close() ;
634  return 0 ;
635 }
636 
643 int vpCalibration::readData(const char* filename)
644 {
645  vpImagePoint ip;
646  std::ifstream f;
647  f.open(filename);
648  if (! f.fail()){
649  unsigned int n ;
650  f >> n ;
651  std::cout << "There are "<< n <<" point on the calibration grid " << std::endl ;
652 
653  clearPoint() ;
654 
655  if (n > 100000)
656  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
657 
658  for (unsigned int i=0 ; i < n ; i++)
659  {
660  double x, y, z, u, v ;
661  f >> x >> y >> z >> u >> v ;
662  std::cout << x <<" "<<y <<" "<<z<<" "<<u<<" "<<v <<std::endl ;
663  ip.set_u( u );
664  ip.set_v( v );
665  addPoint(x, y, z, ip) ;
666  }
667 
668  f.close() ;
669  return 0 ;
670  }
671  else{
672  return -1;
673  }
674 }
691 int vpCalibration::readGrid(const char* filename, unsigned int &n,
692  std::list<double> &oX, std::list<double> &oY, std::list<double> &oZ, bool verbose)
693 {
694  try{
695  std::ifstream f;
696  f.open(filename);
697  if (! f.fail()){
698 
699  f >> n ;
700  if(verbose)
701  std::cout << "There are "<< n <<" points on the calibration grid " << std::endl ;
702  int no_pt;
703  double x,y,z;
704 
705  // clear the list
706  oX.clear();
707  oY.clear();
708  oZ.clear();
709 
710  if (n > 100000)
711  throw(vpException(vpException::badValue, "Bad number of point in the calibration grid"));
712 
713  for (unsigned int i=0 ; i < n ; i++)
714  {
715  f >> no_pt >> x >> y >> z ;
716  if(verbose){
717  std::cout << no_pt <<std::endl ;
718  std::cout << x <<" "<< y <<" "<< z <<std::endl ;
719  }
720  oX.push_back(x) ;
721  oY.push_back(y) ;
722  oZ.push_back(z) ;
723  }
724 
725  f.close() ;
726  }
727  else{
728  return -1;
729  }
730  }
731  catch(...){return -1;}
732  return 0 ;
733 }
734 
746  unsigned int thickness, int subsampling_factor)
747 {
748 
749  for (std::list<vpImagePoint>::const_iterator it = Lip.begin(); it != Lip.end(); ++ it) {
750  vpImagePoint ip = *it;
751  if (subsampling_factor > 1.) {
752  ip.set_u( ip.get_u() / subsampling_factor);
753  ip.set_v( ip.get_v() / subsampling_factor);
754  }
755  vpDisplay::displayCross(I, ip, 12, color, thickness) ;
756  }
757  return 0 ;
758 }
759 
771  unsigned int thickness, int subsampling_factor)
772 {
773  double u0_dist = cam_dist.get_u0() / subsampling_factor;
774  double v0_dist = cam_dist.get_v0() / subsampling_factor;
775  double px_dist = cam_dist.get_px() / subsampling_factor;
776  double py_dist = cam_dist.get_py() / subsampling_factor;
777  double kud_dist = cam_dist.get_kud() ;
778  // double kdu_dist = cam_dist.get_kdu() ;
779 
780  // double u0 = cam.get_u0() ;
781  // double v0 = cam.get_v0() ;
782  // double px = cam.get_px() ;
783  // double py = cam.get_py() ;
784 
785  std::list<double>::const_iterator it_LoX = LoX.begin();
786  std::list<double>::const_iterator it_LoY = LoY.begin();
787  std::list<double>::const_iterator it_LoZ = LoZ.begin();
788 
789  for (unsigned int i =0 ; i < npt ; i++)
790  {
791  double oX = *it_LoX;
792  double oY = *it_LoY;
793  double oZ = *it_LoZ;
794 
795  //double cX = oX*cMo[0][0]+oY*cMo[0][1]+oZ*cMo[0][2] + cMo[0][3];
796  //double cY = oX*cMo[1][0]+oY*cMo[1][1]+oZ*cMo[1][2] + cMo[1][3];
797  //double cZ = oX*cMo[2][0]+oY*cMo[2][1]+oZ*cMo[2][2] + cMo[2][3];
798 
799  //double x = cX/cZ ;
800  //double y = cY/cZ ;
801 
802  // double xp = u0 + x*px ;
803  // double yp = v0 + y*py ;
804 
805  // vpDisplay::displayCross(I,(int)vpMath::round(yp), (int)vpMath::round(xp),
806  // 5,col) ;
807 
808  double cX = oX*cMo_dist[0][0]+oY*cMo_dist[0][1]+oZ*cMo_dist[0][2]+cMo_dist[0][3];
809  double cY = oX*cMo_dist[1][0]+oY*cMo_dist[1][1]+oZ*cMo_dist[1][2]+cMo_dist[1][3];
810  double cZ = oX*cMo_dist[2][0]+oY*cMo_dist[2][1]+oZ*cMo_dist[2][2]+cMo_dist[2][3];
811 
812  double x = cX/cZ ;
813  double y = cY/cZ ;
814 
815  double r2 = 1+kud_dist*(vpMath::sqr(x)+vpMath::sqr(y)) ;
816 
817  vpImagePoint ip;
818  ip.set_u( u0_dist + x*px_dist*r2 );
819  ip.set_v( v0_dist + y*py_dist*r2 );
820 
821  vpDisplay::displayCross(I, ip, 6, color, thickness) ;
823 
824  // std::cout << oX << " " << oY << " " <<oZ << std::endl ;
825  // I.getClick() ;
826  ++it_LoX;
827  ++it_LoY;
828  ++it_LoZ;
829  }
830  return 0;
831 }
double get_v() const
Definition: vpImagePoint.h:268
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.
#define vpERROR_TRACE
Definition: vpDebug.h:391
int readData(const char *filename)
Class to define colors available for display functionnalities.
Definition: vpColor.h:121
double get_u() const
Definition: vpImagePoint.h:257
error that can be emited by ViSP classes.
Definition: vpException.h:73
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)
Point coordinates conversion from pixel coordinates to normalized coordinates in meter...
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:85
Class that defines what is a point.
Definition: vpPoint.h:59
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:221
static double sqr(double x)
Definition: vpMath.h:110
int displayGrid(vpImage< unsigned char > &I, vpColor color=vpColor::yellow, unsigned int thickness=1, int subsampling_factor=1)
vpHomogeneousMatrix cMo_dist
Definition: vpCalibration.h:87
void set_v(const double v)
Definition: vpImagePoint.h:232
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:76
Generic class defining intrinsic camera parameters.
vpHomogeneousMatrix eMc_dist
Definition: vpCalibration.h:98
unsigned int get_npt() const
get the number of points
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
Definition: vpPose.cpp:372
double get_px() const
vpHomogeneousMatrix rMe
reference coordinates (manipulator base coordinates)
Definition: vpCalibration.h:95
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
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
vpCameraParameters cam_dist
projection model with distortion
Definition: vpCalibration.h:92
double get_kdu() const
int writeData(const char *filename)
vpHomogeneousMatrix eMc
position of the camera in relation to the effector
Definition: vpCalibration.h:97
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
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:90
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:145
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:337
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:130