board.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 "board.h"
00029 #include <opencv2/calib3d/calib3d.hpp>
00030 #include <fstream>
00031 using namespace std;
00032 using namespace cv;
00033 namespace aruco {
00034 
00039 BoardConfiguration::BoardConfiguration() { mInfoType = NONE; }
00044 BoardConfiguration::BoardConfiguration(string filePath) throw(cv::Exception) {
00045     mInfoType = NONE;
00046     readFromFile(filePath);
00047 }
00052 BoardConfiguration::BoardConfiguration(const BoardConfiguration &T) : vector< MarkerInfo >(T) {
00053     //     MarkersInfo=T.MarkersInfo;
00054     mInfoType = T.mInfoType;
00055 }
00056 
00061 BoardConfiguration &BoardConfiguration::operator=(const BoardConfiguration &T) {
00062     //     MarkersInfo=T.MarkersInfo;
00063     vector< MarkerInfo >::operator=(T);
00064     mInfoType = T.mInfoType;
00065     return *this;
00066 }
00071 void BoardConfiguration::saveToFile(string sfile) throw(cv::Exception) {
00072 
00073     cv::FileStorage fs(sfile, cv::FileStorage::WRITE);
00074     saveToFile(fs);
00075 }
00078 void BoardConfiguration::saveToFile(cv::FileStorage &fs) throw(cv::Exception) {
00079     fs << "aruco_bc_nmarkers" << (int)size();
00080     fs << "aruco_bc_mInfoType" << (int)mInfoType;
00081     fs << "aruco_bc_markers"
00082        << "[";
00083     for (size_t i = 0; i < size(); i++) {
00084         fs << "{:"
00085            << "id" << at(i).id;
00086 
00087         fs << "corners"
00088            << "[:";
00089         for (int c = 0; c < at(i).size(); c++)
00090             fs << at(i)[c];
00091         fs << "]";
00092         fs << "}";
00093     }
00094     fs << "]";
00095 }
00096 
00101 void BoardConfiguration::readFromFile(string sfile) throw(cv::Exception) {
00102     try {
00103         cv::FileStorage fs(sfile, cv::FileStorage::READ);
00104         readFromFile(fs);
00105     } catch (std::exception &ex) {
00106         throw cv::Exception(81818, "BoardConfiguration::readFromFile", ex.what() + string(" file=)") + sfile, __FILE__, __LINE__);
00107     }
00108 }
00109 
00110 
00113 void BoardConfiguration::readFromFile(cv::FileStorage &fs) throw(cv::Exception) {
00114     int aux = 0;
00115     // look for the nmarkers
00116     if (fs["aruco_bc_nmarkers"].name() != "aruco_bc_nmarkers")
00117         throw cv::Exception(81818, "BoardConfiguration::readFromFile", "invalid file type", __FILE__, __LINE__);
00118     fs["aruco_bc_nmarkers"] >> aux;
00119     resize(aux);
00120     fs["aruco_bc_mInfoType"] >> mInfoType;
00121     cv::FileNode markers = fs["aruco_bc_markers"];
00122     int i = 0;
00123     for (FileNodeIterator it = markers.begin(); it != markers.end(); ++it, i++) {
00124         at(i).id = (*it)["id"];
00125         FileNode FnCorners = (*it)["corners"];
00126         for (FileNodeIterator itc = FnCorners.begin(); itc != FnCorners.end(); ++itc) {
00127             vector< float > coordinates3d;
00128             (*itc) >> coordinates3d;
00129             if (coordinates3d.size() != 3)
00130                 throw cv::Exception(81818, "BoardConfiguration::readFromFile", "invalid file type 3", __FILE__, __LINE__);
00131             cv::Point3f point(coordinates3d[0], coordinates3d[1], coordinates3d[2]);
00132             at(i).push_back(point);
00133         }
00134     }
00135 }
00136 
00139 int BoardConfiguration::getIndexOfMarkerId(int id) const {
00140 
00141     for (size_t i = 0; i < size(); i++)
00142         if (at(i).id == id)
00143             return i;
00144     return -1;
00145 }
00146 
00149 const MarkerInfo &BoardConfiguration::getMarkerInfo(int id) const throw(cv::Exception) {
00150     for (size_t i = 0; i < size(); i++)
00151         if (at(i).id == id)
00152             return at(i);
00153     throw cv::Exception(111, "BoardConfiguration::getMarkerInfo", "Marker with the id given is not found", __FILE__, __LINE__);
00154 }
00155 
00156 
00159 void Board::glGetModelViewMatrix(double modelview_matrix[16]) throw(cv::Exception) {
00160     // check if paremeters are valid
00161     bool invalid = false;
00162     for (int i = 0; i < 3 && !invalid; i++) {
00163         if (Tvec.at< float >(i, 0) != -999999)
00164             invalid |= false;
00165         if (Rvec.at< float >(i, 0) != -999999)
00166             invalid |= false;
00167     }
00168     if (invalid)
00169         throw cv::Exception(9002, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
00170     Mat Rot(3, 3, CV_32FC1), Jacob;
00171     Rodrigues(Rvec, Rot, Jacob);
00172 
00173     double para[3][4];
00174     for (int i = 0; i < 3; i++)
00175         for (int j = 0; j < 3; j++)
00176             para[i][j] = Rot.at< float >(i, j);
00177     // now, add the translation
00178     para[0][3] = Tvec.at< float >(0, 0);
00179     para[1][3] = Tvec.at< float >(1, 0);
00180     para[2][3] = Tvec.at< float >(2, 0);
00181     double scale = 1;
00182 
00183     modelview_matrix[0 + 0 * 4] = para[0][0];
00184     // R1C2
00185     modelview_matrix[0 + 1 * 4] = para[0][1];
00186     modelview_matrix[0 + 2 * 4] = para[0][2];
00187     modelview_matrix[0 + 3 * 4] = para[0][3];
00188     // R2
00189     modelview_matrix[1 + 0 * 4] = para[1][0];
00190     modelview_matrix[1 + 1 * 4] = para[1][1];
00191     modelview_matrix[1 + 2 * 4] = para[1][2];
00192     modelview_matrix[1 + 3 * 4] = para[1][3];
00193     // R3
00194     modelview_matrix[2 + 0 * 4] = -para[2][0];
00195     modelview_matrix[2 + 1 * 4] = -para[2][1];
00196     modelview_matrix[2 + 2 * 4] = -para[2][2];
00197     modelview_matrix[2 + 3 * 4] = -para[2][3];
00198     modelview_matrix[3 + 0 * 4] = 0.0;
00199     modelview_matrix[3 + 1 * 4] = 0.0;
00200     modelview_matrix[3 + 2 * 4] = 0.0;
00201     modelview_matrix[3 + 3 * 4] = 1.0;
00202     if (scale != 0.0) {
00203         modelview_matrix[12] *= scale;
00204         modelview_matrix[13] *= scale;
00205         modelview_matrix[14] *= scale;
00206     }
00207 }
00208 
00209 
00210 /****
00211  *
00212  */
00213 void Board::OgreGetPoseParameters(double position[3], double orientation[4]) throw(cv::Exception) {
00214     // check if paremeters are valid
00215     bool invalid = false;
00216     for (int i = 0; i < 3 && !invalid; i++) {
00217         if (Tvec.at< float >(i, 0) != -999999)
00218             invalid |= false;
00219         if (Rvec.at< float >(i, 0) != -999999)
00220             invalid |= false;
00221     }
00222     if (invalid)
00223         throw cv::Exception(9003, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
00224 
00225     // calculate position vector
00226     position[0] = -Tvec.ptr< float >(0)[0];
00227     position[1] = -Tvec.ptr< float >(0)[1];
00228     position[2] = +Tvec.ptr< float >(0)[2];
00229 
00230     // now calculare orientation quaternion
00231     cv::Mat Rot(3, 3, CV_32FC1);
00232     cv::Rodrigues(Rvec, Rot);
00233 
00234     // calculate axes for quaternion
00235     double stAxes[3][3];
00236     // x axis
00237     stAxes[0][0] = -Rot.at< float >(0, 0);
00238     stAxes[0][1] = -Rot.at< float >(1, 0);
00239     stAxes[0][2] = +Rot.at< float >(2, 0);
00240     // y axis
00241     stAxes[1][0] = -Rot.at< float >(0, 1);
00242     stAxes[1][1] = -Rot.at< float >(1, 1);
00243     stAxes[1][2] = +Rot.at< float >(2, 1);
00244     // for z axis, we use cross product
00245     stAxes[2][0] = stAxes[0][1] * stAxes[1][2] - stAxes[0][2] * stAxes[1][1];
00246     stAxes[2][1] = -stAxes[0][0] * stAxes[1][2] + stAxes[0][2] * stAxes[1][0];
00247     stAxes[2][2] = stAxes[0][0] * stAxes[1][1] - stAxes[0][1] * stAxes[1][0];
00248 
00249     // transposed matrix
00250     double axes[3][3];
00251     axes[0][0] = stAxes[0][0];
00252     axes[1][0] = stAxes[0][1];
00253     axes[2][0] = stAxes[0][2];
00254 
00255     axes[0][1] = stAxes[1][0];
00256     axes[1][1] = stAxes[1][1];
00257     axes[2][1] = stAxes[1][2];
00258 
00259     axes[0][2] = stAxes[2][0];
00260     axes[1][2] = stAxes[2][1];
00261     axes[2][2] = stAxes[2][2];
00262 
00263     // Algorithm in Ken Shoemake's article in 1987 SIGGRAPH course notes
00264     // article "Quaternion Calculus and Fast Animation".
00265     double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
00266     double fRoot;
00267 
00268     if (fTrace > 0.0) {
00269         // |w| > 1/2, may as well choose w > 1/2
00270         fRoot = sqrt(fTrace + 1.0); // 2w
00271         orientation[0] = 0.5 * fRoot;
00272         fRoot = 0.5 / fRoot; // 1/(4w)
00273         orientation[1] = (axes[2][1] - axes[1][2]) * fRoot;
00274         orientation[2] = (axes[0][2] - axes[2][0]) * fRoot;
00275         orientation[3] = (axes[1][0] - axes[0][1]) * fRoot;
00276     } else {
00277         // |w| <= 1/2
00278         static unsigned int s_iNext[3] = {1, 2, 0};
00279         unsigned int i = 0;
00280         if (axes[1][1] > axes[0][0])
00281             i = 1;
00282         if (axes[2][2] > axes[i][i])
00283             i = 2;
00284         unsigned int j = s_iNext[i];
00285         unsigned int k = s_iNext[j];
00286 
00287         fRoot = sqrt(axes[i][i] - axes[j][j] - axes[k][k] + 1.0);
00288         double *apkQuat[3] = {&orientation[1], &orientation[2], &orientation[3]};
00289         *apkQuat[i] = 0.5 * fRoot;
00290         fRoot = 0.5 / fRoot;
00291         orientation[0] = (axes[k][j] - axes[j][k]) * fRoot;
00292         *apkQuat[j] = (axes[j][i] + axes[i][j]) * fRoot;
00293         *apkQuat[k] = (axes[k][i] + axes[i][k]) * fRoot;
00294     }
00295 }
00296 
00299 void Board::draw(cv::Mat &im, cv::Scalar color, int lineWidth, bool writeId) {
00300     for (size_t i = 0; i < size(); i++) {
00301         at(i).draw(im, color, lineWidth, writeId);
00302     }
00303 }
00304 
00307 void Board::saveToFile(string filePath) throw(cv::Exception) {
00308     cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
00309 
00310     fs << "aruco_bo_rvec" << Rvec;
00311     fs << "aruco_bo_tvec" << Tvec;
00312     // now, the markers
00313     fs << "aruco_bo_nmarkers" << (int)size();
00314     fs << "aruco_bo_markers"
00315        << "[";
00316     for (size_t i = 0; i < size(); i++) {
00317         fs << "{:"
00318            << "id" << at(i).id;
00319         fs << "corners"
00320            << "[:";
00321         for (int c = 0; c < at(i).size(); c++)
00322             fs << at(i)[c];
00323         fs << "]";
00324         fs << "}";
00325     }
00326     fs << "]";
00327     // save configuration file
00328     conf.saveToFile(fs);
00329 
00330 
00331 
00332     //  readFromFile(fs);
00333 }
00336 void Board::readFromFile(string filePath) throw(cv::Exception) {
00337     cv::FileStorage fs(filePath, cv::FileStorage::READ);
00338     if (fs["aruco_bo_nmarkers"].name() != "aruco_bo_nmarkers")
00339         throw cv::Exception(81818, "Board::readFromFile", "invalid file type:", __FILE__, __LINE__);
00340 
00341 
00342 
00343     int aux = 0;
00344     // look for the nmarkers
00345     fs["aruco_bo_nmarkers"] >> aux;
00346     resize(aux);
00347     fs["aruco_bo_rvec"] >> Rvec;
00348     fs["aruco_bo_tvec"] >> Tvec;
00349 
00350     cv::FileNode markers = fs["aruco_bo_markers"];
00351     int i = 0;
00352     for (FileNodeIterator it = markers.begin(); it != markers.end(); ++it, i++) {
00353         at(i).id = (*it)["id"];
00354         int ncorners = (*it)["ncorners"];
00355         at(i).resize(ncorners);
00356         FileNode FnCorners = (*it)["corners"];
00357         int c = 0;
00358         for (FileNodeIterator itc = FnCorners.begin(); itc != FnCorners.end(); ++itc, c++) {
00359             vector< float > coordinates2d;
00360             (*itc) >> coordinates2d;
00361             if (coordinates2d.size() != 2)
00362                 throw cv::Exception(81818, "Board::readFromFile", "invalid file type 2", __FILE__, __LINE__);
00363             cv::Point2f point;
00364             point.x = coordinates2d[0];
00365             point.y = coordinates2d[1];
00366             at(i).push_back(point);
00367         }
00368     }
00369 
00370     conf.readFromFile(fs);
00371 }
00372 
00375 void BoardConfiguration::getIdList(std::vector< int > &ids, bool append) const {
00376     if (!append)
00377         ids.clear();
00378     for (size_t i = 0; i < size(); i++)
00379         ids.push_back(at(i).id);
00380 }
00381 };


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