cameraparameters.cpp
Go to the documentation of this file.
00001 /*****************************
00002 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without modification, are
00005 permitted provided that the following conditions are met:
00006 
00007    1. Redistributions of source code must retain the above copyright notice, this list of
00008       conditions and the following disclaimer.
00009 
00010    2. Redistributions in binary form must reproduce the above copyright notice, this list
00011       of conditions and the following disclaimer in the documentation and/or other materials
00012       provided with the distribution.
00013 
00014 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
00015 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00016 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
00017 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00018 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00019 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
00020 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
00021 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00022 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00023 
00024 The views and conclusions contained in the software and documentation are those of the
00025 authors and should not be interpreted as representing official policies, either expressed
00026 or implied, of Rafael Muñoz Salinas.
00027 ********************************/
00028 #include "cameraparameters.h"
00029 #include <fstream>
00030 #include <iostream>
00031 #include <opencv2/core/core.hpp>
00032 #include <opencv2/calib3d/calib3d.hpp>
00033 using namespace std;
00034 namespace aruco {
00035 
00036 
00037 CameraParameters::CameraParameters() {
00038     CameraMatrix = cv::Mat();
00039     Distorsion = cv::Mat();
00040     CamSize = cv::Size(-1, -1);
00041 }
00047 CameraParameters::CameraParameters(cv::Mat cameraMatrix, cv::Mat distorsionCoeff, cv::Size size) throw(cv::Exception) {
00048     setParams(cameraMatrix, distorsionCoeff, size);
00049 }
00052 CameraParameters::CameraParameters(const CameraParameters &CI) {
00053     CI.CameraMatrix.copyTo(CameraMatrix);
00054     CI.Distorsion.copyTo(Distorsion);
00055     CamSize = CI.CamSize;
00056 }
00057 
00060 CameraParameters &CameraParameters::operator=(const CameraParameters &CI) {
00061     CI.CameraMatrix.copyTo(CameraMatrix);
00062     CI.Distorsion.copyTo(Distorsion);
00063     CamSize = CI.CamSize;
00064     return *this;
00065 }
00068 void CameraParameters::setParams(cv::Mat cameraMatrix, cv::Mat distorsionCoeff, cv::Size size) throw(cv::Exception) {
00069     if (cameraMatrix.rows != 3 || cameraMatrix.cols != 3)
00070         throw cv::Exception(9000, "invalid input cameraMatrix", "CameraParameters::setParams", __FILE__, __LINE__);
00071     cameraMatrix.convertTo(CameraMatrix, CV_32FC1);
00072     if (distorsionCoeff.total() < 4 || distorsionCoeff.total() >= 7)
00073         throw cv::Exception(9000, "invalid input distorsionCoeff", "CameraParameters::setParams", __FILE__, __LINE__);
00074     cv::Mat auxD;
00075 
00076     distorsionCoeff.convertTo(Distorsion, CV_32FC1);
00077 
00078     //     Distorsion.create(1,4,CV_32FC1);
00079     //     for (int i=0;i<4;i++)
00080     //         Distorsion.ptr<float>(0)[i]=auxD.ptr<float>(0)[i];
00081 
00082     CamSize = size;
00083 }
00084 
00087 cv::Point3f CameraParameters::getCameraLocation(cv::Mat Rvec, cv::Mat Tvec) {
00088     cv::Mat m33(3, 3, CV_32FC1);
00089     cv::Rodrigues(Rvec, m33);
00090 
00091     cv::Mat m44 = cv::Mat::eye(4, 4, CV_32FC1);
00092     for (int i = 0; i < 3; i++)
00093         for (int j = 0; j < 3; j++)
00094             m44.at< float >(i, j) = m33.at< float >(i, j);
00095 
00096     // now, add translation information
00097     for (int i = 0; i < 3; i++)
00098         m44.at< float >(i, 3) = Tvec.at< float >(0, i);
00099     // invert the matrix
00100     m44.inv();
00101     return cv::Point3f(m44.at< float >(0, 0), m44.at< float >(0, 1), m44.at< float >(0, 2));
00102 }
00103 
00106 void CameraParameters::readFromFile(string path) throw(cv::Exception) {
00107 
00108     ifstream file(path.c_str());
00109     if (!file)
00110         throw cv::Exception(9005, "could not open file:" + path, "CameraParameters::readFromFile", __FILE__, __LINE__);
00111     // Create the matrices
00112     Distorsion = cv::Mat::zeros(4, 1, CV_32FC1);
00113     CameraMatrix = cv::Mat::eye(3, 3, CV_32FC1);
00114     char line[1024];
00115     while (!file.eof()) {
00116         file.getline(line, 1024);
00117         char cmd[20];
00118         float fval;
00119         if (sscanf(line, "%s = %f", cmd, &fval) == 2) {
00120             string scmd(cmd);
00121             if (scmd == "fx")
00122                 CameraMatrix.at< float >(0, 0) = fval;
00123             else if (scmd == "cx")
00124                 CameraMatrix.at< float >(0, 2) = fval;
00125             else if (scmd == "fy")
00126                 CameraMatrix.at< float >(1, 1) = fval;
00127             else if (scmd == "cy")
00128                 CameraMatrix.at< float >(1, 2) = fval;
00129             else if (scmd == "k1")
00130                 Distorsion.at< float >(0, 0) = fval;
00131             else if (scmd == "k2")
00132                 Distorsion.at< float >(1, 0) = fval;
00133             else if (scmd == "p1")
00134                 Distorsion.at< float >(2, 0) = fval;
00135             else if (scmd == "p2")
00136                 Distorsion.at< float >(3, 0) = fval;
00137             else if (scmd == "width")
00138                 CamSize.width = fval;
00139             else if (scmd == "height")
00140                 CamSize.height = fval;
00141         }
00142     }
00143 }
00146 void CameraParameters::saveToFile(string path, bool inXML) throw(cv::Exception) {
00147     if (!isValid())
00148         throw cv::Exception(9006, "invalid object", "CameraParameters::saveToFile", __FILE__, __LINE__);
00149     if (!inXML) {
00150         ofstream file(path.c_str());
00151         if (!file)
00152             throw cv::Exception(9006, "could not open file:" + path, "CameraParameters::saveToFile", __FILE__, __LINE__);
00153         file << "# Aruco 1.0 CameraParameters" << endl;
00154         file << "fx = " << CameraMatrix.at< float >(0, 0) << endl;
00155         file << "cx = " << CameraMatrix.at< float >(0, 2) << endl;
00156         file << "fy = " << CameraMatrix.at< float >(1, 1) << endl;
00157         file << "cy = " << CameraMatrix.at< float >(1, 2) << endl;
00158         file << "k1 = " << Distorsion.at< float >(0, 0) << endl;
00159         file << "k2 = " << Distorsion.at< float >(1, 0) << endl;
00160         file << "p1 = " << Distorsion.at< float >(2, 0) << endl;
00161         file << "p2 = " << Distorsion.at< float >(3, 0) << endl;
00162         file << "width = " << CamSize.width << endl;
00163         file << "height = " << CamSize.height << endl;
00164     } else {
00165         cv::FileStorage fs(path, cv::FileStorage::WRITE);
00166         fs << "image_width" << CamSize.width;
00167         fs << "image_height" << CamSize.height;
00168         fs << "camera_matrix" << CameraMatrix;
00169         fs << "distortion_coefficients" << Distorsion;
00170     }
00171 }
00172 
00175 void CameraParameters::resize(cv::Size size) throw(cv::Exception) {
00176     if (!isValid())
00177         throw cv::Exception(9007, "invalid object", "CameraParameters::resize", __FILE__, __LINE__);
00178     if (size == CamSize)
00179         return;
00180     // now, read the camera size
00181     // resize the camera parameters to fit this image size
00182     float AxFactor = float(size.width) / float(CamSize.width);
00183     float AyFactor = float(size.height) / float(CamSize.height);
00184     CameraMatrix.at< float >(0, 0) *= AxFactor;
00185     CameraMatrix.at< float >(0, 2) *= AxFactor;
00186     CameraMatrix.at< float >(1, 1) *= AyFactor;
00187     CameraMatrix.at< float >(1, 2) *= AyFactor;
00188 }
00189 
00190 /****
00191  *
00192  *
00193  *
00194  *
00195  */
00196 void CameraParameters::readFromXMLFile(string filePath) throw(cv::Exception) {
00197     cv::FileStorage fs(filePath, cv::FileStorage::READ);
00198     int w = -1, h = -1;
00199     cv::Mat MCamera, MDist;
00200 
00201     fs["image_width"] >> w;
00202     fs["image_height"] >> h;
00203     fs["distortion_coefficients"] >> MDist;
00204     fs["camera_matrix"] >> MCamera;
00205 
00206     if (MCamera.cols == 0 || MCamera.rows == 0)
00207         throw cv::Exception(9007, "File :" + filePath + " does not contains valid camera matrix", "CameraParameters::readFromXML", __FILE__, __LINE__);
00208     if (w == -1 || h == 0)
00209         throw cv::Exception(9007, "File :" + filePath + " does not contains valid camera dimensions", "CameraParameters::readFromXML", __FILE__, __LINE__);
00210 
00211     if (MCamera.type() != CV_32FC1)
00212         MCamera.convertTo(CameraMatrix, CV_32FC1);
00213     else
00214         CameraMatrix = MCamera;
00215 
00216     if (MDist.total() < 4)
00217         throw cv::Exception(9007, "File :" + filePath + " does not contains valid distortion_coefficients", "CameraParameters::readFromXML", __FILE__,
00218                             __LINE__);
00219     // convert to 32 and get the 4 first elements only
00220     cv::Mat mdist32;
00221     MDist.convertTo(mdist32, CV_32FC1);
00222     //     Distorsion.create(1,4,CV_32FC1);
00223     //     for (int i=0;i<4;i++)
00224     //         Distorsion.ptr<float>(0)[i]=mdist32.ptr<float>(0)[i];
00225 
00226     Distorsion.create(1, 5, CV_32FC1);
00227     for (int i = 0; i < 5; i++)
00228         Distorsion.ptr< float >(0)[i] = mdist32.ptr< float >(0)[i];
00229     CamSize.width = w;
00230     CamSize.height = h;
00231 }
00232 /****
00233  *
00234  */
00235 void CameraParameters::glGetProjectionMatrix(cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar,
00236                                              bool invert) throw(cv::Exception) {
00237 
00238     if (cv::countNonZero(Distorsion) != 0)
00239         std::cerr << "CameraParameters::glGetProjectionMatrix :: The camera has distortion coefficients " << __FILE__ << " " << __LINE__ << endl;
00240     if (isValid() == false)
00241         throw cv::Exception(9100, "invalid camera parameters", "CameraParameters::glGetProjectionMatrix", __FILE__, __LINE__);
00242 
00243     // Deterime the rsized info
00244     double Ax = double(size.width) / double(orgImgSize.width);
00245     double Ay = double(size.height) / double(orgImgSize.height);
00246     double _fx = CameraMatrix.at< float >(0, 0) * Ax;
00247     double _cx = CameraMatrix.at< float >(0, 2) * Ax;
00248     double _fy = CameraMatrix.at< float >(1, 1) * Ay;
00249     double _cy = CameraMatrix.at< float >(1, 2) * Ay;
00250     double cparam[3][4] = {{_fx, 0, _cx, 0}, {0, _fy, _cy, 0}, {0, 0, 1, 0}};
00251 
00252     argConvGLcpara2(cparam, size.width, size.height, gnear, gfar, proj_matrix, invert);
00253 }
00254 
00255 /*******************
00256  *
00257  *
00258  *******************/
00259 double CameraParameters::norm(double a, double b, double c) { return (sqrt(a * a + b * b + c * c)); }
00260 
00261 /*******************
00262  *
00263  *
00264  *******************/
00265 
00266 double CameraParameters::dot(double a1, double a2, double a3, double b1, double b2, double b3) { return (a1 * b1 + a2 * b2 + a3 * b3); }
00267 
00268 /*******************
00269  *
00270  *
00271  *******************/
00272 
00273 void CameraParameters::argConvGLcpara2(double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert) throw(cv::Exception) {
00274 
00275     double icpara[3][4];
00276     double trans[3][4];
00277     double p[3][3], q[4][4];
00278     int i, j;
00279 
00280     cparam[0][2] *= -1.0;
00281     cparam[1][2] *= -1.0;
00282     cparam[2][2] *= -1.0;
00283 
00284     if (arParamDecompMat(cparam, icpara, trans) < 0)
00285         throw cv::Exception(9002, "parameter error", "MarkerDetector::argConvGLcpara2", __FILE__, __LINE__);
00286 
00287     for (i = 0; i < 3; i++) {
00288         for (j = 0; j < 3; j++) {
00289             p[i][j] = icpara[i][j] / icpara[2][2];
00290         }
00291     }
00292     q[0][0] = (2.0 * p[0][0] / width);
00293     q[0][1] = (2.0 * p[0][1] / width);
00294     q[0][2] = ((2.0 * p[0][2] / width) - 1.0);
00295     q[0][3] = 0.0;
00296 
00297     q[1][0] = 0.0;
00298     q[1][1] = (2.0 * p[1][1] / height);
00299     q[1][2] = ((2.0 * p[1][2] / height) - 1.0);
00300     q[1][3] = 0.0;
00301 
00302     q[2][0] = 0.0;
00303     q[2][1] = 0.0;
00304     q[2][2] = (gfar + gnear) / (gfar - gnear);
00305     q[2][3] = -2.0 * gfar * gnear / (gfar - gnear);
00306 
00307     q[3][0] = 0.0;
00308     q[3][1] = 0.0;
00309     q[3][2] = 1.0;
00310     q[3][3] = 0.0;
00311 
00312     for (i = 0; i < 4; i++) {
00313         for (j = 0; j < 3; j++) {
00314             m[i + j * 4] = q[i][0] * trans[0][j] + q[i][1] * trans[1][j] + q[i][2] * trans[2][j];
00315         }
00316         m[i + 3 * 4] = q[i][0] * trans[0][3] + q[i][1] * trans[1][3] + q[i][2] * trans[2][3] + q[i][3];
00317     }
00318 
00319     if (!invert) {
00320         m[13] = -m[13];
00321         m[1] = -m[1];
00322         m[5] = -m[5];
00323         m[9] = -m[9];
00324     }
00325 }
00326 /*******************
00327  *
00328  *
00329  *******************/
00330 
00331 int CameraParameters::arParamDecompMat(double source[3][4], double cpara[3][4], double trans[3][4]) throw(cv::Exception) {
00332     int r, c;
00333     double Cpara[3][4];
00334     double rem1, rem2, rem3;
00335 
00336     if (source[2][3] >= 0) {
00337         for (r = 0; r < 3; r++) {
00338             for (c = 0; c < 4; c++) {
00339                 Cpara[r][c] = source[r][c];
00340             }
00341         }
00342     } else {
00343         for (r = 0; r < 3; r++) {
00344             for (c = 0; c < 4; c++) {
00345                 Cpara[r][c] = -(source[r][c]);
00346             }
00347         }
00348     }
00349 
00350     for (r = 0; r < 3; r++) {
00351         for (c = 0; c < 4; c++) {
00352             cpara[r][c] = 0.0;
00353         }
00354     }
00355     cpara[2][2] = norm(Cpara[2][0], Cpara[2][1], Cpara[2][2]);
00356     trans[2][0] = Cpara[2][0] / cpara[2][2];
00357     trans[2][1] = Cpara[2][1] / cpara[2][2];
00358     trans[2][2] = Cpara[2][2] / cpara[2][2];
00359     trans[2][3] = Cpara[2][3] / cpara[2][2];
00360 
00361     cpara[1][2] = dot(trans[2][0], trans[2][1], trans[2][2], Cpara[1][0], Cpara[1][1], Cpara[1][2]);
00362     rem1 = Cpara[1][0] - cpara[1][2] * trans[2][0];
00363     rem2 = Cpara[1][1] - cpara[1][2] * trans[2][1];
00364     rem3 = Cpara[1][2] - cpara[1][2] * trans[2][2];
00365     cpara[1][1] = norm(rem1, rem2, rem3);
00366     trans[1][0] = rem1 / cpara[1][1];
00367     trans[1][1] = rem2 / cpara[1][1];
00368     trans[1][2] = rem3 / cpara[1][1];
00369 
00370     cpara[0][2] = dot(trans[2][0], trans[2][1], trans[2][2], Cpara[0][0], Cpara[0][1], Cpara[0][2]);
00371     cpara[0][1] = dot(trans[1][0], trans[1][1], trans[1][2], Cpara[0][0], Cpara[0][1], Cpara[0][2]);
00372     rem1 = Cpara[0][0] - cpara[0][1] * trans[1][0] - cpara[0][2] * trans[2][0];
00373     rem2 = Cpara[0][1] - cpara[0][1] * trans[1][1] - cpara[0][2] * trans[2][1];
00374     rem3 = Cpara[0][2] - cpara[0][1] * trans[1][2] - cpara[0][2] * trans[2][2];
00375     cpara[0][0] = norm(rem1, rem2, rem3);
00376     trans[0][0] = rem1 / cpara[0][0];
00377     trans[0][1] = rem2 / cpara[0][0];
00378     trans[0][2] = rem3 / cpara[0][0];
00379 
00380     trans[1][3] = (Cpara[1][3] - cpara[1][2] * trans[2][3]) / cpara[1][1];
00381     trans[0][3] = (Cpara[0][3] - cpara[0][1] * trans[1][3] - cpara[0][2] * trans[2][3]) / cpara[0][0];
00382 
00383     for (r = 0; r < 3; r++) {
00384         for (c = 0; c < 3; c++) {
00385             cpara[r][c] /= cpara[2][2];
00386         }
00387     }
00388 
00389     return 0;
00390 }
00391 
00392 
00393 /******
00394  *
00395  */
00396 void CameraParameters::OgreGetProjectionMatrix(cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar,
00397                                                bool invert) throw(cv::Exception) {
00398     double temp_matrix[16];
00399     (*this).glGetProjectionMatrix(orgImgSize, size, temp_matrix, gnear, gfar, invert);
00400     proj_matrix[0] = -temp_matrix[0];
00401     proj_matrix[1] = -temp_matrix[4];
00402     proj_matrix[2] = -temp_matrix[8];
00403     proj_matrix[3] = temp_matrix[12];
00404 
00405     proj_matrix[4] = -temp_matrix[1];
00406     proj_matrix[5] = -temp_matrix[5];
00407     proj_matrix[6] = -temp_matrix[9];
00408     proj_matrix[7] = temp_matrix[13];
00409 
00410     proj_matrix[8] = -temp_matrix[2];
00411     proj_matrix[9] = -temp_matrix[6];
00412     proj_matrix[10] = -temp_matrix[10];
00413     proj_matrix[11] = temp_matrix[14];
00414 
00415     proj_matrix[12] = -temp_matrix[3];
00416     proj_matrix[13] = -temp_matrix[7];
00417     proj_matrix[14] = -temp_matrix[11];
00418     proj_matrix[15] = temp_matrix[15];
00419 }
00420 /******
00421  *
00422  */
00423 
00424 cv::Mat CameraParameters::getRTMatrix(const cv::Mat &R_, const cv::Mat &T_, int forceType) {
00425     cv::Mat M;
00426     cv::Mat R, T;
00427     R_.copyTo(R);
00428     T_.copyTo(T);
00429     if (R.type() == CV_64F) {
00430         assert(T.type() == CV_64F);
00431         cv::Mat Matrix = cv::Mat::eye(4, 4, CV_64FC1);
00432 
00433         cv::Mat R33 = cv::Mat(Matrix, cv::Rect(0, 0, 3, 3));
00434         if (R.total() == 3) {
00435             cv::Rodrigues(R, R33);
00436         } else if (R.total() == 9) {
00437             cv::Mat R64;
00438             R.convertTo(R64, CV_64F);
00439             R.copyTo(R33);
00440         }
00441         for (int i = 0; i < 3; i++)
00442             Matrix.at< double >(i, 3) = T.ptr< double >(0)[i];
00443         M = Matrix;
00444     } else if (R.depth() == CV_32F) {
00445         cv::Mat Matrix = cv::Mat::eye(4, 4, CV_32FC1);
00446         cv::Mat R33 = cv::Mat(Matrix, cv::Rect(0, 0, 3, 3));
00447         if (R.total() == 3) {
00448             cv::Rodrigues(R, R33);
00449         } else if (R.total() == 9) {
00450             cv::Mat R32;
00451             R.convertTo(R32, CV_32F);
00452             R.copyTo(R33);
00453         }
00454 
00455         for (int i = 0; i < 3; i++)
00456             Matrix.at< float >(i, 3) = T.ptr< float >(0)[i];
00457         M = Matrix;
00458     }
00459 
00460     if (forceType == -1)
00461         return M;
00462     else {
00463         cv::Mat MTyped;
00464         M.convertTo(MTyped, forceType);
00465         return MTyped;
00466     }
00467 }
00468 };


asr_aruco_marker_recognition
Author(s): Allgeyer Tobias, Meißner Pascal, Qattan Mohamad
autogenerated on Thu Jun 6 2019 21:14:12