28 #include <aruco/cameraparameters.h> 31 #include <opencv2/opencv.hpp> 37 CameraParameters::CameraParameters() {
38 CameraMatrix=cv::Mat();
40 CamSize=cv::Size(-1,-1);
47 CameraParameters::CameraParameters(cv::Mat cameraMatrix,cv::Mat distorsionCoeff,cv::Size size)
throw(cv::Exception) {
48 setParams(cameraMatrix,distorsionCoeff,size);
52 CameraParameters::CameraParameters(
const CameraParameters &CI) {
53 CI.CameraMatrix.copyTo(CameraMatrix);
54 CI.Distorsion.copyTo(Distorsion);
60 CameraParameters & CameraParameters::operator=(
const CameraParameters &CI) {
61 CI.CameraMatrix.copyTo(CameraMatrix);
62 CI.Distorsion.copyTo(Distorsion);
68 void CameraParameters::setParams(cv::Mat cameraMatrix,cv::Mat distorsionCoeff,cv::Size size)
throw(cv::Exception)
70 if (cameraMatrix.rows!=3 || cameraMatrix.cols!=3)
71 throw cv::Exception(9000,
"invalid input cameraMatrix",
"CameraParameters::setParams",__FILE__,__LINE__);
72 cameraMatrix.convertTo(CameraMatrix,CV_32FC1);
73 if ( distorsionCoeff.total()<4 || distorsionCoeff.total()>=7 )
74 throw cv::Exception(9000,
"invalid input distorsionCoeff",
"CameraParameters::setParams",__FILE__,__LINE__);
77 distorsionCoeff.convertTo( Distorsion,CV_32FC1);
89 cv::Point3f CameraParameters::getCameraLocation(cv::Mat Rvec,cv::Mat Tvec)
91 cv::Mat m33(3,3,CV_32FC1);
92 cv::Rodrigues(Rvec, m33) ;
94 cv::Mat m44=cv::Mat::eye(4,4,CV_32FC1);
97 m44.at<
float>(i,j)=m33.at<
float>(i,j);
100 for (
int i=0;i<3;i++)
101 m44.at<
float>(i,3)=Tvec.at<
float>(0,i);
104 return cv::Point3f( m44.at<
float>(0,0),m44.at<
float>(0,1),m44.at<
float>(0,2));
110 void CameraParameters::readFromFile(
string path)
throw(cv::Exception)
113 ifstream file(path.c_str());
114 if (!file)
throw cv::Exception(9005,
"could not open file:"+path,
"CameraParameters::readFromFile",__FILE__,__LINE__);
116 Distorsion=cv::Mat::zeros(4,1,CV_32FC1);
117 CameraMatrix=cv::Mat::eye(3,3,CV_32FC1);
119 while (!file.eof()) {
120 file.getline(line,1024);
123 if ( sscanf(line,
"%s = %f",cmd,&fval)==2) {
125 if (scmd==
"fx") CameraMatrix.at<
float>(0,0)=fval;
126 else if (scmd==
"cx") CameraMatrix.at<
float>(0,2)=fval;
127 else if (scmd==
"fy") CameraMatrix.at<
float>(1,1)=fval;
128 else if (scmd==
"cy") CameraMatrix.at<
float>(1,2)=fval;
129 else if (scmd==
"k1") Distorsion.at<
float>(0,0)=fval;
130 else if (scmd==
"k2") Distorsion.at<
float>(1,0)=fval;
131 else if (scmd==
"p1") Distorsion.at<
float>(2,0)=fval;
132 else if (scmd==
"p2") Distorsion.at<
float>(3,0)=fval;
133 else if (scmd==
"width") CamSize.width=fval;
134 else if (scmd==
"height") CamSize.height=fval;
140 void CameraParameters::saveToFile(
string path,
bool inXML)
throw(cv::Exception)
142 if (!isValid())
throw cv::Exception(9006,
"invalid object",
"CameraParameters::saveToFile",__FILE__,__LINE__);
144 ofstream file(path.c_str());
145 if (!file)
throw cv::Exception(9006,
"could not open file:"+path,
"CameraParameters::saveToFile",__FILE__,__LINE__);
146 file<<
"# Aruco 1.0 CameraParameters"<<endl;
147 file<<
"fx = "<<CameraMatrix.at<
float>(0,0)<<endl;
148 file<<
"cx = "<<CameraMatrix.at<
float>(0,2)<<endl;
149 file<<
"fy = "<<CameraMatrix.at<
float>(1,1)<<endl;
150 file<<
"cy = "<<CameraMatrix.at<
float>(1,2)<<endl;
151 file<<
"k1 = "<<Distorsion.at<
float>(0,0)<<endl;
152 file<<
"k2 = "<<Distorsion.at<
float>(1,0)<<endl;
153 file<<
"p1 = "<<Distorsion.at<
float>(2,0)<<endl;
154 file<<
"p2 = "<<Distorsion.at<
float>(3,0)<<endl;
155 file<<
"width = "<<CamSize.width<<endl;
156 file<<
"height = "<<CamSize.height<<endl;
159 cv::FileStorage fs(path,cv::FileStorage::WRITE);
160 fs<<
"image_width" << CamSize.width;
161 fs<<
"image_height" << CamSize.height;
162 fs<<
"camera_matrix" << CameraMatrix;
163 fs<<
"distortion_coefficients" <<Distorsion;
169 void CameraParameters::resize(cv::Size size)
throw(cv::Exception)
171 if (!isValid())
throw cv::Exception(9007,
"invalid object",
"CameraParameters::resize",__FILE__,__LINE__);
172 if (size==CamSize)
return;
175 float AxFactor= float(size.width)/ float(CamSize.width);
176 float AyFactor= float(size.height)/ float(CamSize.height);
177 CameraMatrix.at<
float>(0,0)*=AxFactor;
178 CameraMatrix.at<
float>(0,2)*=AxFactor;
179 CameraMatrix.at<
float>(1,1)*=AyFactor;
180 CameraMatrix.at<
float>(1,2)*=AyFactor;
189 void CameraParameters::readFromXMLFile(
string filePath)
throw(cv::Exception)
191 cv::FileStorage fs(filePath, cv::FileStorage::READ);
193 cv::Mat MCamera,MDist;
195 fs[
"image_width"] >> w;
196 fs[
"image_height"] >> h;
197 fs[
"distortion_coefficients"] >> MDist;
198 fs[
"camera_matrix"] >> MCamera;
200 if (MCamera.cols==0 || MCamera.rows==0)
throw cv::Exception(9007,
"File :"+filePath+
" does not contains valid camera matrix",
"CameraParameters::readFromXML",__FILE__,__LINE__);
201 if (w==-1 || h==0)
throw cv::Exception(9007,
"File :"+filePath+
" does not contains valid camera dimensions",
"CameraParameters::readFromXML",__FILE__,__LINE__);
203 if (MCamera.type()!=CV_32FC1) MCamera.convertTo(CameraMatrix,CV_32FC1);
204 else CameraMatrix=MCamera;
206 if (MDist.total()<4)
throw cv::Exception(9007,
"File :"+filePath+
" does not contains valid distortion_coefficients",
"CameraParameters::readFromXML",__FILE__,__LINE__);
209 MDist.convertTo(mdist32,CV_32FC1);
210 Distorsion.create(1,4,CV_32FC1);
211 for (
int i=0;i<4;i++)
212 Distorsion.ptr<
float>(0)[i]=mdist32.ptr<
float>(0)[i];
220 void CameraParameters::glGetProjectionMatrix( cv::Size orgImgSize, cv::Size size,
double proj_matrix[16],
double gnear,
double gfar,
bool invert )
throw(cv::Exception)
223 if (cv::countNonZero(Distorsion)!=0) std::cerr<<
"CameraParameters::glGetProjectionMatrix :: The camera has distortion coefficients " <<__FILE__<<
" "<<__LINE__<<endl;
224 if (isValid()==
false)
throw cv::Exception(9100,
"invalid camera parameters",
"CameraParameters::glGetProjectionMatrix",__FILE__,__LINE__);
227 double Ax=double(size.width)/double(orgImgSize.width);
228 double Ay=double(size.height)/double(orgImgSize.height);
229 double _fx=CameraMatrix.at<
float>(0,0)*Ax;
230 double _cx=CameraMatrix.at<
float>(0,2)*Ax;
231 double _fy=CameraMatrix.at<
float>(1,1)*Ay;
232 double _cy=CameraMatrix.at<
float>(1,2)*Ay;
233 double cparam[3][4] =
242 argConvGLcpara2( cparam, size.width, size.height, gnear, gfar, proj_matrix, invert );
250 double CameraParameters::norm(
double a,
double b,
double c )
252 return( sqrt( a*a + b*b + c*c ) );
260 double CameraParameters::dot(
double a1,
double a2,
double a3,
261 double b1,
double b2,
double b3 )
263 return( a1 * b1 + a2 * b2 + a3 * b3 );
271 void CameraParameters::argConvGLcpara2(
double cparam[3][4],
int width,
int height,
double gnear,
double gfar,
double m[16],
bool invert )
throw(cv::Exception)
276 double p[3][3], q[4][4];
279 cparam[0][2] *= -1.0;
280 cparam[1][2] *= -1.0;
281 cparam[2][2] *= -1.0;
283 if ( arParamDecompMat(cparam, icpara, trans) < 0 )
284 throw cv::Exception(9002,
"parameter error",
"MarkerDetector::argConvGLcpara2",__FILE__,__LINE__);
286 for ( i = 0; i < 3; i++ )
288 for ( j = 0; j < 3; j++ )
290 p[i][j] = icpara[i][j] / icpara[2][2];
293 q[0][0] = (2.0 * p[0][0] / width);
294 q[0][1] = (2.0 * p[0][1] / width);
295 q[0][2] = ((2.0 * p[0][2] / width) - 1.0);
299 q[1][1] = (2.0 * p[1][1] / height);
300 q[1][2] = ((2.0 * p[1][2] / height) - 1.0);
305 q[2][2] = (gfar + gnear)/(gfar - gnear);
306 q[2][3] = -2.0 * gfar * gnear / (gfar - gnear);
313 for ( i = 0; i < 4; i++ )
315 for ( j = 0; j < 3; j++ )
317 m[i+j*4] = q[i][0] * trans[0][j]
318 + q[i][1] * trans[1][j]
319 + q[i][2] * trans[2][j];
321 m[i+3*4] = q[i][0] * trans[0][3]
322 + q[i][1] * trans[1][3]
323 + q[i][2] * trans[2][3]
341 int CameraParameters::arParamDecompMat(
double source[3][4],
double cpara[3][4],
double trans[3][4] )
throw(cv::Exception)
345 double rem1, rem2, rem3;
347 if ( source[2][3] >= 0 )
349 for ( r = 0; r < 3; r++ )
351 for ( c = 0; c < 4; c++ )
353 Cpara[r][c] = source[r][c];
359 for ( r = 0; r < 3; r++ )
361 for ( c = 0; c < 4; c++ )
363 Cpara[r][c] = -(source[r][c]);
368 for ( r = 0; r < 3; r++ )
370 for ( c = 0; c < 4; c++ )
375 cpara[2][2] = norm( Cpara[2][0], Cpara[2][1], Cpara[2][2] );
376 trans[2][0] = Cpara[2][0] / cpara[2][2];
377 trans[2][1] = Cpara[2][1] / cpara[2][2];
378 trans[2][2] = Cpara[2][2] / cpara[2][2];
379 trans[2][3] = Cpara[2][3] / cpara[2][2];
381 cpara[1][2] =
dot( trans[2][0], trans[2][1], trans[2][2],
382 Cpara[1][0], Cpara[1][1], Cpara[1][2] );
383 rem1 = Cpara[1][0] - cpara[1][2] * trans[2][0];
384 rem2 = Cpara[1][1] - cpara[1][2] * trans[2][1];
385 rem3 = Cpara[1][2] - cpara[1][2] * trans[2][2];
386 cpara[1][1] = norm( rem1, rem2, rem3 );
387 trans[1][0] = rem1 / cpara[1][1];
388 trans[1][1] = rem2 / cpara[1][1];
389 trans[1][2] = rem3 / cpara[1][1];
391 cpara[0][2] =
dot( trans[2][0], trans[2][1], trans[2][2],
392 Cpara[0][0], Cpara[0][1], Cpara[0][2] );
393 cpara[0][1] =
dot( trans[1][0], trans[1][1], trans[1][2],
394 Cpara[0][0], Cpara[0][1], Cpara[0][2] );
395 rem1 = Cpara[0][0] - cpara[0][1]*trans[1][0] - cpara[0][2]*trans[2][0];
396 rem2 = Cpara[0][1] - cpara[0][1]*trans[1][1] - cpara[0][2]*trans[2][1];
397 rem3 = Cpara[0][2] - cpara[0][1]*trans[1][2] - cpara[0][2]*trans[2][2];
398 cpara[0][0] = norm( rem1, rem2, rem3 );
399 trans[0][0] = rem1 / cpara[0][0];
400 trans[0][1] = rem2 / cpara[0][0];
401 trans[0][2] = rem3 / cpara[0][0];
403 trans[1][3] = (Cpara[1][3] - cpara[1][2]*trans[2][3]) / cpara[1][1];
404 trans[0][3] = (Cpara[0][3] - cpara[0][1]*trans[1][3]
405 - cpara[0][2]*trans[2][3]) / cpara[0][0];
407 for ( r = 0; r < 3; r++ )
409 for ( c = 0; c < 3; c++ )
411 cpara[r][c] /= cpara[2][2];
422 void CameraParameters::OgreGetProjectionMatrix(cv::Size orgImgSize, cv::Size size,
double proj_matrix[16],
double gnear,
double gfar,
bool invert)
throw(cv::Exception)
424 double temp_matrix[16];
425 (*this).glGetProjectionMatrix(orgImgSize, size, temp_matrix, gnear, gfar, invert);
426 proj_matrix[0]=-temp_matrix[0];
427 proj_matrix[1]=-temp_matrix[4];
428 proj_matrix[2]=-temp_matrix[8];
429 proj_matrix[3]=temp_matrix[12];
431 proj_matrix[4]=-temp_matrix[1];
432 proj_matrix[5]=-temp_matrix[5];
433 proj_matrix[6]=-temp_matrix[9];
434 proj_matrix[7]=temp_matrix[13];
436 proj_matrix[8]=-temp_matrix[2];
437 proj_matrix[9]=-temp_matrix[6];
438 proj_matrix[10]=-temp_matrix[10];
439 proj_matrix[11]=temp_matrix[14];
441 proj_matrix[12]=-temp_matrix[3];
442 proj_matrix[13]=-temp_matrix[7];
443 proj_matrix[14]=-temp_matrix[11];
444 proj_matrix[15]=temp_matrix[15];
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
TFSIMD_FORCE_INLINE const tfScalar & w() const