Visual Servoing Platform  version 3.6.1 under development (2025-03-11)
vpHandEyeCalibration.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Hand-eye calibration.
32  */
33 
34 #include <cmath> // std::fabs
35 #include <limits> // numeric_limits
36 
37 #include <visp3/vision/vpHandEyeCalibration.h>
38 
39 #define DEBUG_LEVEL1 0
40 #define DEBUG_LEVEL2 0
41 
42 BEGIN_VISP_NAMESPACE
43 
56  void vpHandEyeCalibration::calibrationVerifrMo(const std::vector<vpHomogeneousMatrix> &cMo,
57  const std::vector<vpHomogeneousMatrix> &rMe,
58  const vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &mean_rMo)
59 {
60  unsigned int nbPose = (unsigned int)cMo.size();
61  std::vector<vpTranslationVector> rTo(nbPose);
62  std::vector<vpRotationMatrix> rRo(nbPose);
63 
64  for (unsigned int i = 0; i < nbPose; ++i) {
65  vpHomogeneousMatrix rMo = rMe[i] * eMc * cMo[i];
66  rRo[i] = rMo.getRotationMatrix();
67  rTo[i] = rMo.getTranslationVector();
68  }
71 
72  mean_rMo.buildFrom(meanTrans, meanRot);
73 
74 #if DEBUG_LEVEL2
75  {
76  std::cout << "Mean rMo " << std::endl;
77  std::cout << "Translation: " << meanTrans.t() << std::endl;
78  vpThetaUVector P(meanRot);
79  std::cout << "Rotation : theta (deg) = " << vpMath::deg(sqrt(P.sumSquare())) << " Matrix : " << std::endl
80  << meanRot << std::endl;
81  std::cout << "theta U (deg): " << vpMath::deg(P[0]) << " " << vpMath::deg(P[1]) << " " << vpMath::deg(P[2])
82  << std::endl;
83  }
84 #endif
85 
86  // standard deviation, rotational part
87  double resRot = 0.0;
88  for (unsigned int i = 0; i < nbPose; ++i) {
89  vpRotationMatrix R = meanRot.t() * rRo[i]; // Rm^T Ri
90  vpThetaUVector P(R);
91  // theta = Riemannian distance d(Rm,Ri)
92  double theta = sqrt(P.sumSquare());
93  std::cout << "Distance theta between rMo/rMc(" << i << ") and mean (deg) = " << vpMath::deg(theta) << std::endl;
94  // Euclidean distance d(Rm,Ri) not used
95  // theta = 2.0*sqrt(2.0)*sin(theta/2.0);
96  resRot += theta * theta;
97  }
98  resRot = sqrt(resRot / nbPose);
99  std::cout << "Mean residual rMo/rMc(" << nbPose << ") - rotation (deg) = " << vpMath::deg(resRot) << std::endl;
100  // standard deviation, translational part
101  double resTrans = 0.0;
102  for (unsigned int i = 0; i < nbPose; ++i) {
103  vpColVector errTrans = vpColVector(rTo[i] - meanTrans);
104  resTrans += errTrans.sumSquare();
105  std::cout << "Distance d between rMo/rMc(" << i << ") and mean (m) = " << sqrt(errTrans.sumSquare()) << std::endl;
106  }
107  resTrans = sqrt(resTrans / nbPose);
108  std::cout << "Mean residual rMo/rMc(" << nbPose << ") - translation (m) = " << resTrans << std::endl;
109  double resPos = (resRot * resRot + resTrans * resTrans) * nbPose;
110  resPos = sqrt(resPos / (2 * nbPose));
111  std::cout << "Mean residual rMo/rMc(" << nbPose << ") - global = " << resPos << std::endl;
112 }
113 
124 void vpHandEyeCalibration::calibrationVerifrMo(const std::vector<vpHomogeneousMatrix> &cMo,
125  const std::vector<vpHomogeneousMatrix> &rMe,
126  const vpHomogeneousMatrix &eMc)
127 {
129  rMo.eye();
130  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc, rMo);
131 }
143 int vpHandEyeCalibration::calibrationRotationProcrustes(const std::vector<vpHomogeneousMatrix> &cMo,
144  const std::vector<vpHomogeneousMatrix> &rMe,
145  vpRotationMatrix &eRc)
146 {
147  // Method by solving the orthogonal Procrustes problem
148  // [... (theta u)_e ...] = eRc [ ... (theta u)_c ...]
149  // similar to E^T = eRc C^T below
150 
151  vpMatrix Et, Ct;
152  vpMatrix A;
153  unsigned int k = 0;
154  unsigned int nbPose = (unsigned int)cMo.size();
155 
156  // for all couples ij
157  for (unsigned int i = 0; i < nbPose; ++i) {
158  vpRotationMatrix rRei, ciRo;
159  rMe[i].extract(rRei);
160  cMo[i].extract(ciRo);
161  // std::cout << "rMei: " << std::endl << rMe[i] << std::endl;
162 
163  for (unsigned int j = 0; j < nbPose; ++j) {
164  if (j > i) // we don't use two times same couples...
165  {
166  vpRotationMatrix rRej, cjRo;
167  rMe[j].extract(rRej);
168  cMo[j].extract(cjRo);
169  // std::cout << "rMej: " << std::endl << rMe[j] << std::endl;
170 
171  vpRotationMatrix ejRei = rRej.t() * rRei;
172  vpThetaUVector ejPei(ejRei);
173  vpColVector xe = vpColVector(ejPei);
174 
175  vpRotationMatrix cjRci = cjRo * ciRo.t();
176  vpThetaUVector cjPci(cjRci);
177  vpColVector xc = vpColVector(cjPci);
178 
179  if (k == 0) {
180  Et = xe.t();
181  Ct = xc.t();
182  }
183  else {
184  Et.stack(xe.t());
185  Ct.stack(xc.t());
186  }
187  k++;
188  }
189  }
190  }
191  // std::cout << "Et " << std::endl << Et << std::endl;
192  // std::cout << "Ct " << std::endl << Ct << std::endl;
193 
194  // R obtained from the SVD of (E C^T) with all singular values equal to 1
195  A = Et.t() * Ct;
196  vpMatrix M, U, V;
197  vpColVector sv;
198  int rank = A.pseudoInverse(M, sv, 1e-6, U, V);
199  if (rank != 3)
200  return -1;
201  A = U * V.t();
202  eRc = vpRotationMatrix(A);
203 
204 #if DEBUG_LEVEL2
205  {
206  vpThetaUVector ePc(eRc);
207  std::cout << "Rotation from Procrustes method " << std::endl;
208  std::cout << "theta U (deg): " << vpMath::deg(ePc[0]) << " " << vpMath::deg(ePc[1]) << " " << vpMath::deg(ePc[2])
209  << std::endl;
210  // Residual
211  vpMatrix residual;
212  residual = A * Ct.t() - Et.t();
213  // std::cout << "Residual: " << std::endl << residual << std::endl;
214  double res = sqrt(residual.sumSquare() / (residual.getRows() * residual.getCols()));
215  printf("Mean residual (rotation) = %lf\n", res);
216  }
217 #endif
218  return 0;
219 }
220 
233 int vpHandEyeCalibration::calibrationRotationTsai(const std::vector<vpHomogeneousMatrix> &cMo,
234  const std::vector<vpHomogeneousMatrix> &rMe, vpRotationMatrix &eRc)
235 {
236  vpMatrix A;
237  vpColVector B;
238  unsigned int nbPose = (unsigned int)cMo.size();
239  unsigned int k = 0;
240  // for all couples ij
241  for (unsigned int i = 0; i < nbPose; ++i) {
242  vpRotationMatrix rRei, ciRo;
243  rMe[i].extract(rRei);
244  cMo[i].extract(ciRo);
245  // std::cout << "rMei: " << std::endl << rMe[i] << std::endl;
246 
247  for (unsigned int j = 0; j < nbPose; ++j) {
248  if (j > i) { // we don't use two times same couples...
249  vpRotationMatrix rRej, cjRo;
250  rMe[j].extract(rRej);
251  cMo[j].extract(cjRo);
252  // std::cout << "rMej: " << std::endl << rMe[j] << std::endl;
253 
254  vpRotationMatrix ejRei = rRej.t() * rRei;
255  vpThetaUVector ejPei(ejRei);
256 
257  vpRotationMatrix cjRci = cjRo * ciRo.t();
258  vpThetaUVector cjPci(cjRci);
259  // std::cout << "theta U (camera) " << cjPci.t() << std::endl;
260 
261  vpMatrix As;
262  vpColVector b(3);
263 
264  As = vpColVector::skew(vpColVector(ejPei) + vpColVector(cjPci));
265 
266  b = (vpColVector)cjPci - (vpColVector)ejPei; // A.40
267 
268  if (k == 0) {
269  A = As;
270  B = b;
271  }
272  else {
273  A = vpMatrix::stack(A, As);
274  B = vpColVector::stack(B, b);
275  }
276  k++;
277  }
278  }
279  }
280 #if DEBUG_LEVEL2
281  {
282  std::cout << "Tsai method: system A X = B " << std::endl;
283  std::cout << "A " << std::endl << A << std::endl;
284  std::cout << "B " << std::endl << B << std::endl;
285  }
286 #endif
287  vpMatrix Ap;
288  // the linear system A x = B is solved
289  // using x = A^+ B
290 
291  int rank = A.pseudoInverse(Ap);
292  if (rank != 3)
293  return -1;
294 
295  vpColVector x = Ap * B;
296 
297  // extraction of theta U
298 
299  // x = tan(theta/2) U
300  double norm = x.sumSquare();
301  double c = 1 / sqrt(1 + norm); // cos(theta/2)
302  double alpha = acos(c); // theta/2
303  norm = 2.0 * c / vpMath::sinc(alpha); // theta / tan(theta/2)
304  for (unsigned int i = 0; i < 3; ++i) {
305  x[i] *= norm;
306  }
307 
308  // Building of the rotation matrix eRc
309  vpThetaUVector xP(x[0], x[1], x[2]);
310  eRc = vpRotationMatrix(xP);
311 
312 #if DEBUG_LEVEL2
313  {
314  std::cout << "Rotation from Tsai method" << std::endl;
315  std::cout << "theta U (deg): " << vpMath::deg(x[0]) << " " << vpMath::deg(x[1]) << " " << vpMath::deg(x[2])
316  << std::endl;
317  // Residual
318  for (unsigned int i = 0; i < 3; ++i) {
319  x[i] /= norm; /* original x */
320  }
321  vpColVector residual;
322  residual = A * x - B;
323  // std::cout << "Residual: " << std::endl << residual << std::endl;
324  double res = sqrt(residual.sumSquare() / residual.getRows());
325  printf("Mean residual (rotation) = %lf\n", res);
326  }
327 #endif
328  return 0;
329 }
330 
343 int vpHandEyeCalibration::calibrationRotationTsaiOld(const std::vector<vpHomogeneousMatrix> &cMo,
344  const std::vector<vpHomogeneousMatrix> &rMe, vpRotationMatrix &eRc)
345 {
346  unsigned int nbPose = (unsigned int)cMo.size();
347  vpMatrix A;
348  vpColVector B;
349  vpColVector x;
350  unsigned int k = 0;
351  // for all couples ij
352  for (unsigned int i = 0; i < nbPose; ++i) {
353  vpRotationMatrix rRei, ciRo;
354  rMe[i].extract(rRei);
355  cMo[i].extract(ciRo);
356  // std::cout << "rMei: " << std::endl << rMe[i] << std::endl;
357 
358  for (unsigned int j = 0; j < nbPose; ++j) {
359  if (j > i) { // we don't use two times same couples...
360  vpRotationMatrix rRej, cjRo;
361  rMe[j].extract(rRej);
362  cMo[j].extract(cjRo);
363  // std::cout << "rMej: " << std::endl << rMe[j] << std::endl;
364 
365  vpRotationMatrix rReij = rRej.t() * rRei;
366 
367  vpRotationMatrix cijRo = cjRo * ciRo.t();
368 
369  vpThetaUVector rPeij(rReij);
370 
371  double theta = sqrt(rPeij[0] * rPeij[0] + rPeij[1] * rPeij[1] + rPeij[2] * rPeij[2]);
372 
373  // std::cout << i << " " << j << " " << "ejRei: " << std::endl << rReij << std::endl;
374  // std::cout << "theta (robot) " << theta << std::endl;
375  // std::cout << "theta U (robot) " << rPeij << std::endl;
376  // std::cout << "cjRci: " << std::endl << cijRo.t() << std::endl;
377 
378  for (unsigned int m = 0; m < 3; m++) {
379  rPeij[m] = rPeij[m] * vpMath::sinc(theta / 2);
380  }
381 
382  vpThetaUVector cijPo(cijRo);
383  theta = sqrt(cijPo[0] * cijPo[0] + cijPo[1] * cijPo[1] + cijPo[2] * cijPo[2]);
384  for (unsigned int m = 0; m < 3; m++) {
385  cijPo[m] = cijPo[m] * vpMath::sinc(theta / 2);
386  }
387 
388  // std::cout << "theta (camera) " << theta << std::endl;
389  // std::cout << "theta U (camera) " << cijPo.t() << std::endl;
390 
391  vpMatrix As;
392  vpColVector b(3);
393 
394  As = vpColVector::skew(vpColVector(rPeij) + vpColVector(cijPo));
395 
396  b = (vpColVector)cijPo - (vpColVector)rPeij; // A.40
397 
398  if (k == 0) {
399  A = As;
400  B = b;
401  }
402  else {
403  A = vpMatrix::stack(A, As);
404  B = vpColVector::stack(B, b);
405  }
406  k++;
407  }
408  }
409  }
410 
411  // std::cout << "A " << std::endl << A << std::endl;
412  // std::cout << "B " << std::endl << B << std::endl;
413 
414  // the linear system is defined
415  // x = AtA^-1AtB is solved
416  vpMatrix AtA = A.AtA();
417 
418  vpMatrix Ap;
419  int rank = AtA.pseudoInverse(Ap, 1e-6);
420  if (rank != 3)
421  return -1;
422 
423  x = Ap * A.t() * B;
424  vpColVector x2 = x; // For residual computation
425 
426  // extraction of theta and U
427  double theta;
428  double d = x.sumSquare();
429  for (unsigned int i = 0; i < 3; ++i) {
430  x[i] = 2 * x[i] / sqrt(1 + d);
431  }
432  theta = sqrt(x.sumSquare()) / 2;
433  theta = 2 * asin(theta);
434  // if (theta !=0)
435  if (std::fabs(theta) > std::numeric_limits<double>::epsilon()) {
436  for (unsigned int i = 0; i < 3; ++i) {
437  x[i] *= theta / (2 * sin(theta / 2));
438  }
439  }
440  else {
441  x = 0;
442  }
443 
444  // Building of the rotation matrix eRc
445  vpThetaUVector xP(x[0], x[1], x[2]);
446  eRc = vpRotationMatrix(xP);
447 
448 #if DEBUG_LEVEL2
449  {
450  std::cout << "Rotation from Old Tsai method" << std::endl;
451  std::cout << "theta U (deg): " << vpMath::deg(x[0]) << " " << vpMath::deg(x[1]) << " " << vpMath::deg(x[2])
452  << std::endl;
453  // Residual
454  vpColVector residual;
455  residual = A * x2 - B;
456  // std::cout << "Residual: " << std::endl << residual << std::endl;
457  double res = sqrt(residual.sumSquare() / residual.getRows());
458  printf("Mean residual (rotation) = %lf\n", res);
459  }
460 #endif
461  return 0;
462 }
463 
477 int vpHandEyeCalibration::calibrationTranslation(const std::vector<vpHomogeneousMatrix> &cMo,
478  const std::vector<vpHomogeneousMatrix> &rMe, vpRotationMatrix &eRc,
479  vpTranslationVector &eTc)
480 {
481  vpMatrix I3(3, 3);
482  I3.eye();
483  unsigned int k = 0;
484  unsigned int nbPose = (unsigned int)cMo.size();
485  vpMatrix A(3 * nbPose, 3);
486  vpColVector B(3 * nbPose);
487  // Building of the system for the translation estimation
488  // for all couples ij
489  for (unsigned int i = 0; i < nbPose; ++i) {
490  for (unsigned int j = 0; j < nbPose; ++j) {
491  if (j > i) { // we don't use two times same couples...
492  vpHomogeneousMatrix ejMei = rMe[j].inverse() * rMe[i];
493  vpHomogeneousMatrix cjMci = cMo[j] * cMo[i].inverse();
494 
495  vpRotationMatrix ejRei, cjRci;
496  vpTranslationVector ejTei, cjTci;
497 
498  ejMei.extract(ejRei);
499  ejMei.extract(ejTei);
500 
501  cjMci.extract(cjRci);
502  cjMci.extract(cjTci);
503 
504  vpMatrix a = vpMatrix(ejRei) - I3;
505  vpTranslationVector b = eRc * cjTci - ejTei;
506 
507  if (k == 0) {
508  A = a;
509  B = b;
510  }
511  else {
512  A = vpMatrix::stack(A, a);
513  B = vpColVector::stack(B, vpColVector(b));
514  }
515  k++;
516  }
517  }
518  }
519 
520  // the linear system A x = B is solved
521  // using x = A^+ B
522  vpMatrix Ap;
523  int rank = A.pseudoInverse(Ap);
524  if (rank != 3)
525  return -1;
526 
527  vpColVector x = Ap * B;
528  eTc = (vpTranslationVector)x;
529 
530 #if DEBUG_LEVEL2
531  {
532  printf("New Hand-eye calibration : ");
533  std::cout << "Translation: " << eTc[0] << " " << eTc[1] << " " << eTc[2] << std::endl;
534  // residual
535  vpColVector residual;
536  residual = A * x - B;
537  // std::cout << "Residual: " << std::endl << residual << std::endl;
538  double res = sqrt(residual.sumSquare() / residual.getRows());
539  printf("Mean residual (translation) = %lf\n", res);
540  }
541 #endif
542  return 0;
543 }
544 
558 int vpHandEyeCalibration::calibrationTranslationOld(const std::vector<vpHomogeneousMatrix> &cMo,
559  const std::vector<vpHomogeneousMatrix> &rMe, vpRotationMatrix &eRc,
560  vpTranslationVector &eTc)
561 {
562  vpMatrix A;
563  vpColVector B;
564  // Building of the system for the translation estimation
565  // for all couples ij
566  vpRotationMatrix I3;
567  I3.eye();
568  int k = 0;
569  unsigned int nbPose = (unsigned int)cMo.size();
570 
571  for (unsigned int i = 0; i < nbPose; ++i) {
572  vpRotationMatrix rRei, ciRo;
573  vpTranslationVector rTei, ciTo;
574  rMe[i].extract(rRei);
575  cMo[i].extract(ciRo);
576  rMe[i].extract(rTei);
577  cMo[i].extract(ciTo);
578 
579  for (unsigned int j = 0; j < nbPose; ++j) {
580  if (j > i) { // we don't use two times same couples...
581  vpRotationMatrix rRej, cjRo;
582  rMe[j].extract(rRej);
583  cMo[j].extract(cjRo);
584 
585  vpTranslationVector rTej, cjTo;
586  rMe[j].extract(rTej);
587  cMo[j].extract(cjTo);
588 
589  vpRotationMatrix rReij = rRej.t() * rRei;
590 
591  vpTranslationVector rTeij = rTej + (-rTei);
592 
593  rTeij = rRej.t() * rTeij;
594 
595  vpMatrix a = vpMatrix(rReij) - vpMatrix(I3);
596 
598  b = eRc * cjTo - rReij * eRc * ciTo + rTeij;
599 
600  if (k == 0) {
601  A = a;
602  B = b;
603  }
604  else {
605  A = vpMatrix::stack(A, a);
606  B = vpColVector::stack(B, vpColVector(b));
607  }
608  k++;
609  }
610  }
611  }
612 
613  // the linear system is solved
614  // x = AtA^-1AtB is solved
615  vpMatrix AtA = A.AtA();
616  vpMatrix Ap;
617  vpColVector AeTc;
618  int rank = AtA.pseudoInverse(Ap, 1e-6);
619  if (rank != 3) {
620  return -1;
621  }
622 
623  AeTc = Ap * A.t() * B;
624  eTc = (vpTranslationVector)AeTc;
625 
626 #if DEBUG_LEVEL2
627  {
628  printf("Old Hand-eye calibration : ");
629  std::cout << "Translation: " << eTc[0] << " " << eTc[1] << " " << eTc[2] << std::endl;
630 
631  // residual
632  vpColVector residual;
633  residual = A * AeTc - B;
634  // std::cout << "Residual: " << std::endl << residual << std::endl;
635  double res = 0;
636  for (unsigned int i = 0; i < residual.getRows(); ++i) {
637  res += residual[i] * residual[i];
638  }
639  res = sqrt(res / residual.getRows());
640  printf("Mean residual (translation) = %lf\n", res);
641  }
642 #endif
643  return 0;
644 }
645 
657 double vpHandEyeCalibration::calibrationErrVVS(const std::vector<vpHomogeneousMatrix> &cMo,
658  const std::vector<vpHomogeneousMatrix> &rMe,
659  const vpHomogeneousMatrix &eMc, vpColVector &errVVS)
660 {
661  unsigned int nbPose = (unsigned int)cMo.size();
662  vpMatrix I3(3, 3);
663  I3.eye();
664  vpRotationMatrix eRc;
666  eMc.extract(eRc);
667  eMc.extract(eTc);
668 
669  unsigned int k = 0;
670  for (unsigned int i = 0; i < nbPose; ++i) {
671  for (unsigned int j = 0; j < nbPose; ++j) {
672  if (j > i) { // we don't use two times same couples...
673  vpColVector s(3);
674 
675  vpHomogeneousMatrix ejMei = rMe[j].inverse() * rMe[i];
676  vpHomogeneousMatrix cjMci = cMo[j] * cMo[i].inverse();
677 
678  vpRotationMatrix ejRei, cjRci;
679  vpTranslationVector ejTei, cjTci;
680 
681  ejMei.extract(ejRei);
682  vpThetaUVector ejPei(ejRei);
683  ejMei.extract(ejTei);
684 
685  cjMci.extract(cjRci);
686  vpThetaUVector cjPci(cjRci);
687  cjMci.extract(cjTci);
688  // terms due to rotation
689  s = vpMatrix(eRc) * vpColVector(cjPci) - vpColVector(ejPei);
690  if (k == 0) {
691  errVVS = s;
692  }
693  else {
694  errVVS = vpColVector::stack(errVVS, s);
695  }
696  k++;
697  // terms due to translation
698  s = (vpMatrix(ejRei) - I3) * eTc - eRc * cjTci + ejTei;
699  errVVS = vpColVector::stack(errVVS, s);
700  } // enf if i > j
701  } // end for j
702  } // end for i
703 
704  double resRot, resTrans, resPos;
705  resRot = resTrans = resPos = 0.0;
706  for (unsigned int i = 0; i < (unsigned int)errVVS.size(); i += 6) {
707  resRot += errVVS[i] * errVVS[i];
708  resRot += errVVS[i + 1] * errVVS[i + 1];
709  resRot += errVVS[i + 2] * errVVS[i + 2];
710  resTrans += errVVS[i + 3] * errVVS[i + 3];
711  resTrans += errVVS[i + 4] * errVVS[i + 4];
712  resTrans += errVVS[i + 5] * errVVS[i + 5];
713  }
714  resPos = resRot + resTrans;
715  resRot = sqrt(resRot * 2 / errVVS.size());
716  resTrans = sqrt(resTrans * 2 / errVVS.size());
717  resPos = sqrt(resPos / errVVS.size());
718 #if DEBUG_LEVEL1
719  {
720  printf("Mean VVS residual - rotation (deg) = %lf\n", vpMath::deg(resRot));
721  printf("Mean VVS residual - translation = %lf\n", resTrans);
722  printf("Mean VVS residual - global = %lf\n", resPos);
723  }
724 #endif
725  return resPos;
726 }
727 
738 int vpHandEyeCalibration::calibrationVVS(const std::vector<vpHomogeneousMatrix> &cMo,
739  const std::vector<vpHomogeneousMatrix> &rMe, vpHomogeneousMatrix &eMc)
740 {
741  unsigned int it = 0;
742  unsigned int nb_iter_max = 30;
743  double res = 1.0;
744  unsigned int nbPose = (unsigned int)cMo.size();
745  vpColVector err;
746  vpMatrix L;
747  vpMatrix I3(3, 3);
748  I3.eye();
749  vpRotationMatrix eRc;
751  eMc.extract(eRc);
752  eMc.extract(eTc);
753 
754  /* FC : on recalcule 2 fois tous les ejMei et cjMci a chaque iteration
755  alors qu'ils sont constants. Ce serait sans doute mieux de les
756  calculer une seule fois et de les stocker. Pourraient alors servir
757  dans les autres fonctions HandEye. A voir si vraiment interessant vu la
758  combinatoire. Idem pour les theta u */
759  while ((res > 1e-7) && (it < nb_iter_max)) {
760  /* compute s - s^* */
761  vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, err);
762  /* compute L_s */
763  unsigned int k = 0;
764  for (unsigned int i = 0; i < nbPose; ++i) {
765  for (unsigned int j = 0; j < nbPose; ++j) {
766  if (j > i) // we don't use two times same couples...
767  {
768  vpMatrix Ls(3, 6), Lv(3, 3), Lw(3, 3);
769 
770  vpHomogeneousMatrix ejMei = rMe[j].inverse() * rMe[i];
771  vpHomogeneousMatrix cjMci = cMo[j] * cMo[i].inverse();
772 
773  vpRotationMatrix ejRei;
774  ejMei.extract(ejRei);
775  vpThetaUVector cjPci(cjMci);
776 
777  vpTranslationVector cjTci;
778 
779  cjMci.extract(cjTci);
780  // terms due to rotation
781  // Lv.diag(0.0); //
782  Lv = 0.0;
783  Lw = -vpMatrix(eRc) * vpColVector::skew(vpColVector(cjPci));
784  for (unsigned int m = 0; m < 3; m++)
785  for (unsigned int n = 0; n < 3; n++) {
786  Ls[m][n] = Lv[m][n];
787  Ls[m][n + 3] = Lw[m][n];
788  }
789  if (k == 0) {
790  L = Ls;
791  }
792  else {
793  L = vpMatrix::stack(L, Ls);
794  }
795  k++;
796  // terms due to translation
797  Lv = (vpMatrix(ejRei) - I3) * vpMatrix(eRc);
798  Lw = vpMatrix(eRc) * vpColVector::skew(vpColVector(cjTci));
799  for (unsigned int m = 0; m < 3; m++)
800  for (unsigned int n = 0; n < 3; n++) {
801  Ls[m][n] = Lv[m][n];
802  Ls[m][n + 3] = Lw[m][n];
803  }
804  L = vpMatrix::stack(L, Ls);
805 
806  } // enf if i > j
807  } // end for j
808  } // end for i
809  double lambda = 0.9;
810  vpMatrix Lp;
811  int rank = L.pseudoInverse(Lp);
812  if (rank != 6)
813  return -1;
814 
815  vpColVector e = Lp * err;
816  vpColVector v = -e * lambda;
817  // std::cout << "e: " << e.t() << std::endl;
818  eMc = eMc * vpExponentialMap::direct(v);
819  eMc.extract(eRc);
820  eMc.extract(eTc);
821  res = sqrt(v.sumSquare() / v.getRows());
822  it++;
823  } // end while
824 #if DEBUG_LEVEL2
825  {
826  printf(" Iteration number for NL hand-eye minimization : %d\n", it);
827  vpThetaUVector ePc(eRc);
828  std::cout << "theta U (deg): " << vpMath::deg(ePc[0]) << " " << vpMath::deg(ePc[1]) << " " << vpMath::deg(ePc[2])
829  << std::endl;
830  std::cout << "Translation: " << eTc[0] << " " << eTc[1] << " " << eTc[2] << std::endl;
831  // Residual
832  double res = err.sumSquare();
833  res = sqrt(res / err.getRows());
834  printf("Mean residual (rotation+translation) = %lf\n", res);
835  }
836 #endif
837  if (it == nb_iter_max) {
838  return 1; // VVS has not converged before nb_iter_max
839  }
840  else {
841  return 0;
842  }
843 }
844 
845 
846 int vpHandEyeCalibration::calibrate(const std::vector<vpHomogeneousMatrix> &cMo,
847  const std::vector<vpHomogeneousMatrix> &rMe, vpHomogeneousMatrix &eMc)
848 {
849  int err;
851  rMo.eye();
852  err = vpHandEyeCalibration::calibrate(cMo, rMe, eMc, rMo);
853  return err;
854 }
855 
856 #define HE_I 0
857 #define HE_TSAI_OROT 1
858 #define HE_TSAI_ORNT 2
859 #define HE_TSAI_NROT 3
860 #define HE_TSAI_NRNT 4
861 #define HE_PROCRUSTES_OT 5
862 #define HE_PROCRUSTES_NT 6
863 
864 int vpHandEyeCalibration::calibrate(const std::vector<vpHomogeneousMatrix> &cMo,
865  const std::vector<vpHomogeneousMatrix> &rMe,
867 {
868  if (cMo.size() != rMe.size()) {
869  throw vpException(vpException::dimensionError, "cMo and rMe have different sizes");
870  }
871 
872  vpRotationMatrix eRc;
874  vpColVector errVVS;
875  double resPos;
876 
877  /* initialisation of eMc and rMo to I in case all other methods fail */
878  eMc.eye();
879  rMo.eye();
880  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
881  double vmin = resPos; // will serve to determine the best method
882 #if DEBUG_LEVEL1
883  int He_method = HE_I; // will serve to know which is the best method
884 #endif
885  vpHomogeneousMatrix eMcMin = eMc; // best initial estimation for VSS
886  // Method using Old Tsai implementation
887  int err = vpHandEyeCalibration::calibrationRotationTsaiOld(cMo, rMe, eRc);
888  if (err != 0) {
889  std::cout << "\nProblem in solving Hand-Eye Rotation by Old Tsai method" << std::endl;
890  }
891  else {
892  eMc.insert(eRc);
893  err = vpHandEyeCalibration::calibrationTranslationOld(cMo, rMe, eRc, eTc);
894  if (err != 0) {
895  std::cout << "\nProblem in solving Hand-Eye Translation by Old Tsai method after Old Tsai method for rotation" << std::endl;
896  }
897  else {
898  eMc.insert(eTc);
899 #if DEBUG_LEVEL1
900  {
901  std::cout << "\nRotation by (old) Tsai, old implementation for translation" << std::endl;
902  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
903  }
904 #endif
905  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
906  if (resPos < vmin) {
907  vmin = resPos;
908  eMcMin = eMc;
909 #if DEBUG_LEVEL1
910  He_method = HE_TSAI_OROT;
911 #endif
912  }
913  }
914  err = vpHandEyeCalibration::calibrationTranslation(cMo, rMe, eRc, eTc);
915  if (err != 0) {
916  std::cout << "\n Problem in solving Hand-Eye Translation after Old Tsai method for rotation" << std::endl;
917  }
918  else {
919  eMc.insert(eTc);
920 #if DEBUG_LEVEL1
921  {
922  std::cout << "\nRotation by (old) Tsai, new implementation for translation" << std::endl;
923  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
924  }
925 #endif
926  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
927  if (resPos < vmin) {
928  vmin = resPos;
929  eMcMin = eMc;
930 #if DEBUG_LEVEL1
931  He_method = HE_TSAI_ORNT;
932 #endif
933  }
934  }
935  }
936  // First method using Tsai formulation
937  err = vpHandEyeCalibration::calibrationRotationTsai(cMo, rMe, eRc);
938  if (err != 0) {
939  std::cout << "\n Problem in solving Hand-Eye Rotation by Tsai method" << std::endl;
940  }
941  else {
942  eMc.insert(eRc);
943  err = vpHandEyeCalibration::calibrationTranslationOld(cMo, rMe, eRc, eTc);
944  if (err != 0) {
945  std::cout << "\n Problem in solving Hand-Eye Translation by Old Tsai method after Tsai method for rotation" << std::endl;
946  }
947  else {
948  eMc.insert(eTc);
949 #if DEBUG_LEVEL1
950  {
951  std::cout << "\nRotation by Tsai, old implementation for translation" << std::endl;
952  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
953  }
954 #endif
955  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
956  if (resPos < vmin) {
957  vmin = resPos;
958  eMcMin = eMc;
959 #if DEBUG_LEVEL1
960  He_method = HE_TSAI_NROT;
961 #endif
962  }
963  }
964  err = vpHandEyeCalibration::calibrationTranslation(cMo, rMe, eRc, eTc);
965  if (err != 0) {
966  std::cout << "\n Problem in solving Hand-Eye Translation after Tsai method for rotation" << std::endl;
967  }
968  else {
969  eMc.insert(eTc);
970 #if DEBUG_LEVEL1
971  {
972  std::cout << "\nRotation by Tsai, new implementation for translation" << std::endl;
973  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
974  }
975 #endif
976  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
977  if (resPos < vmin) {
978  vmin = resPos;
979  eMcMin = eMc;
980 #if DEBUG_LEVEL1
981  He_method = HE_TSAI_NRNT;
982 #endif
983  }
984  }
985  }
986  // Second method by solving the orthogonal Procrustes problem
987  err = vpHandEyeCalibration::calibrationRotationProcrustes(cMo, rMe, eRc);
988  if (err != 0)
989  std::cout << "\n Problem in solving Hand-Eye Rotation by Procrustes method" << std::endl;
990  else {
991  eMc.insert(eRc);
992  err = vpHandEyeCalibration::calibrationTranslationOld(cMo, rMe, eRc, eTc);
993  if (err != 0) {
994  std::cout << "\n Problem in solving Hand-Eye Translation by Old Tsai method after Procrustes method for rotation" << std::endl;
995  }
996  else {
997  eMc.insert(eTc);
998 #if DEBUG_LEVEL1
999  {
1000  std::cout << "\nRotation by Procrustes, old implementation for translation" << std::endl;
1001  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
1002  }
1003 #endif
1004  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
1005  if (resPos < vmin) {
1006  vmin = resPos;
1007  eMcMin = eMc;
1008 #if DEBUG_LEVEL1
1009  He_method = HE_PROCRUSTES_OT;
1010 #endif
1011  }
1012  }
1013  err = vpHandEyeCalibration::calibrationTranslation(cMo, rMe, eRc, eTc);
1014  if (err != 0) {
1015  std::cout << "\n Problem in solving Hand-Eye Translation after Procrustes method for rotation" << std::endl;
1016  }
1017  else {
1018  eMc.insert(eTc);
1019 #if DEBUG_LEVEL1
1020  {
1021  std::cout << "\nRotation by Procrustes, new implementation for translation" << std::endl;
1022  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc);
1023  }
1024 #endif
1025  resPos = vpHandEyeCalibration::calibrationErrVVS(cMo, rMe, eMc, errVVS);
1026  if (resPos < vmin) {
1027  eMcMin = eMc;
1028 #if DEBUG_LEVEL1
1029  vmin = resPos;
1030  He_method = HE_PROCRUSTES_NT;
1031 #endif
1032  }
1033  }
1034  }
1035 
1036  /* determination of the best method in case at least one succeeds */
1037  eMc = eMcMin;
1038 #if DEBUG_LEVEL1
1039  {
1040  if (He_method == HE_I) {
1041  std::cout << "Best method : I !!!, vmin = " << vmin << std::endl;
1042  }
1043  if (He_method == HE_TSAI_OROT) {
1044  std::cout << "Best method : TSAI_OROT, vmin = " << vmin << std::endl;
1045  }
1046  if (He_method == HE_TSAI_ORNT) {
1047  std::cout << "Best method : TSAI_ORNT, vmin = " << vmin << std::endl;
1048  }
1049  if (He_method == HE_TSAI_NROT) {
1050  std::cout << "Best method : TSAI_NROT, vmin = " << vmin << std::endl;
1051  }
1052  if (He_method == HE_TSAI_NRNT) {
1053  std::cout << "Best method : TSAI_NRNT, vmin = " << vmin << std::endl;
1054  }
1055  if (He_method == HE_PROCRUSTES_OT) {
1056  std::cout << "Best method : PROCRUSTES_OT, vmin = " << vmin << std::endl;
1057  }
1058  if (He_method == HE_PROCRUSTES_NT) {
1059  std::cout << "Best method : PROCRUSTES_NT, vmin = " << vmin << std::endl;
1060  }
1061  vpThetaUVector ePc(eMc);
1062  std::cout << "theta U (deg): " << vpMath::deg(ePc[0]) << " " << vpMath::deg(ePc[1]) << " " << vpMath::deg(ePc[2])
1063  << std::endl;
1064  std::cout << "Translation: " << eMc[0][3] << " " << eMc[1][3] << " " << eMc[2][3] << std::endl;
1065  }
1066 #endif
1067 
1068  // Non linear iterative minimization to estimate simultaneouslty eRc and eTc
1069  err = vpHandEyeCalibration::calibrationVVS(cMo, rMe, eMc);
1070  // err : 0 si tout OK, -1 si pb de rang, 1 si pas convergence
1071  if (err != 0) {
1072  std::cout << "\n Problem in solving Hand-Eye Calibration by VVS" << std::endl;
1073  }
1074  else {
1075  // printf("\nRotation and translation after VVS\n");
1076  vpHandEyeCalibration::calibrationVerifrMo(cMo, rMe, eMc, rMo);
1077  }
1078  return err;
1079 }
1080 
1081 #undef HE_I
1082 #undef HE_TSAI_OROT
1083 #undef HE_TSAI_ORNT
1084 #undef HE_TSAI_NROT
1085 #undef HE_TSAI_NRNT
1086 #undef HE_PROCRUSTES_OT
1087 #undef HE_PROCRUSTES_NT
1088 
1089 #undef DEBUG_LEVEL1
1090 #undef DEBUG_LEVEL2
1091 
1092 END_VISP_NAMESPACE
unsigned int getCols() const
Definition: vpArray2D.h:417
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:429
unsigned int getRows() const
Definition: vpArray2D.h:427
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double sumSquare() const
void stack(double d)
static vpMatrix skew(const vpColVector &v)
vpRowVector t() const
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ dimensionError
Bad dimension.
Definition: vpException.h:71
static vpHomogeneousMatrix direct(const vpColVector &v)
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &rMo)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
void extract(vpRotationMatrix &R) const
void insert(const vpRotationMatrix &R)
static double sinc(double x)
Definition: vpMath.cpp:268
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
void stack(const vpMatrix &A)
vpMatrix AtA() const
vpMatrix pseudoInverse(double svThreshold=1e-6) const
double sumSquare() const
Definition: vpMatrix.cpp:1977
vpMatrix t() const
Implementation of a rotation matrix and operations on such kind of matrices.
vpRotationMatrix t() const
static vpRotationMatrix mean(const std::vector< vpHomogeneousMatrix > &vec_M)
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
static vpTranslationVector mean(const std::vector< vpHomogeneousMatrix > &vec_M)
vpRowVector t() const