Example of Tsai calibration to estimate extrinsic camera parameters, ie hand-eye homogeneous transformation.
#include <stdio.h>
#include <sstream>
#include <iomanip>
#include <vector>
#include <visp/vpDebug.h>
#include <visp/vpParseArgv.h>
#include <visp/vpIoTools.h>
#include <visp/vpCalibration.h>
#include <visp/vpExponentialMap.h>
int main()
{
const int N = 6;
std::vector<vpHomogeneousMatrix> cMo(N) ;
std::vector<vpHomogeneousMatrix> wMe(N) ;
std::cout << "Simulated hand to eye transformation: eMc " << std::endl ;
std::cout << eMc << std::endl ;
for (int i=0 ; i < N ; i++)
{
v_c = 0 ;
if (i==0) {
cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0);
wMe[0].buildFrom(0, 0, 0, 0, 0, 0);
}
else if (i==1)
v_c[3] = M_PI/8 ;
else if (i==2)
v_c[4] = M_PI/8 ;
else if (i==3)
v_c[5] = M_PI/10 ;
else if (i==4)
v_c[0] = 0.5 ;
else if (i==5)
v_c[1] = 0.8 ;
if (i > 0) {
wMe[i] = wMe[i-1] * eMc * cMc * eMc.
inverse();
}
}
if (0) {
for (int i=0 ; i < N ; i++) {
wMo = wMe[i] * eMc * cMo[i];
std::cout << std::endl << "wMo[" << i << "] " << std::endl ;
std::cout << wMo << std::endl ;
std::cout << "cMo[" << i << "] " << std::endl ;
std::cout << cMo[i] << std::endl ;
std::cout << "wMe[" << i << "] " << std::endl ;
std::cout << wMe[i] << std::endl ;
}
}
std::cout << std::endl << "Output: hand to eye calibration result: eMc estimated " << std::endl ;
std::cout << eMc << std::endl ;
return 0 ;
}