highlyreliablemarkers.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 
00029 #include "highlyreliablemarkers.h"
00030 #include <iostream>
00031 using namespace std;
00032 
00033 namespace aruco {
00034 
00035 // static variables from HighlyReliableMarkers. Need to be here to avoid linking errors
00036 Dictionary HighlyReliableMarkers::_D;
00037 HighlyReliableMarkers::BalancedBinaryTree HighlyReliableMarkers::_binaryTree;
00038 unsigned int HighlyReliableMarkers::_n, HighlyReliableMarkers::_ncellsBorder, HighlyReliableMarkers::_correctionDistance;
00039 int HighlyReliableMarkers::_swidth;
00040 
00041 
00044 MarkerCode::MarkerCode(unsigned int n) {
00045     // resize bits vectors and initialize to 0
00046     for (unsigned int i = 0; i < 4; i++) {
00047         _bits[i].resize(n * n);
00048         for (unsigned int j = 0; j < _bits[i].size(); j++)
00049             _bits[i][j] = 0;
00050         _ids[i] = 0; // ids are also 0
00051     }
00052     _n = n;
00053 };
00054 
00055 
00058 MarkerCode::MarkerCode(const MarkerCode &MC) {
00059     for (unsigned int i = 0; i < 4; i++) {
00060         _bits[i] = MC._bits[i];
00061         _ids[i] = MC._ids[i];
00062     }
00063     _n = MC._n;
00064 }
00065 
00066 
00067 
00070 void MarkerCode::set(unsigned int pos, bool val, bool updateIds) {
00071     // if not the same value
00072     if (get(pos) != val) {
00073         for (unsigned int i = 0; i < 4; i++) {         // calculate bit coordinates for each rotation
00074             unsigned int y = pos / n(), x = pos % n(); // if rotation 0, dont do anything
00075                                                        // else calculate bit position in that rotation
00076             if (i == 1) {
00077                 unsigned int aux = y;
00078                 y = x;
00079                 x = n() - aux - 1;
00080             } else if (i == 2) {
00081                 y = n() - y - 1;
00082                 x = n() - x - 1;
00083             } else if (i == 3) {
00084                 unsigned int aux = y;
00085                 y = n() - x - 1;
00086                 x = aux;
00087             }
00088             unsigned int rotPos = y * n() + x; // calculate position in the unidimensional string
00089             _bits[i][rotPos] = val;            // modify value
00090                                                // update identifier in that rotation
00091             if(updateIds) {
00092                 if (val == true)
00093                     _ids[i] += (unsigned int)pow(float(2), float(rotPos)); // if 1, add 2^pos
00094                 else
00095                     _ids[i] -= (unsigned int)pow(float(2), float(rotPos)); // if 0, substract 2^pos
00096             }
00097         }
00098     }
00099 }
00100 
00101 
00104 unsigned int MarkerCode::selfDistance(unsigned int &minRot) const {
00105     unsigned int res = _bits[0].size();    // init to n*n (max value)
00106     for (unsigned int i = 1; i < 4; i++) { // self distance is not calculated for rotation 0
00107         unsigned int hammdist = hammingDistance(_bits[0], _bits[i]);
00108         if (hammdist < res) {
00109             minRot = i;
00110             res = hammdist;
00111         }
00112     }
00113     return res;
00114 }
00115 
00116 
00119 unsigned int MarkerCode::distance(const MarkerCode &m, unsigned int &minRot) const {
00120     unsigned int res = _bits[0].size(); // init to n*n (max value)
00121     for (unsigned int i = 0; i < 4; i++) {
00122         unsigned int hammdist = hammingDistance(_bits[0], m.getRotation(i));
00123         if (hammdist < res) {
00124             minRot = i;
00125             res = hammdist;
00126         }
00127     }
00128     return res;
00129 };
00130 
00131 
00134 void MarkerCode::fromString(std::string s) {
00135     for (unsigned int i = 0; i < s.length(); i++) {
00136         if (s[i] == '0')
00137             set(i, false);
00138         else
00139             set(i, true);
00140     }
00141 }
00142 
00145 std::string MarkerCode::toString() const {
00146     std::string s;
00147     s.resize(size());
00148     for (unsigned int i = 0; i < size(); i++) {
00149         if (get(i))
00150             s[i] = '1';
00151         else
00152             s[i] = '0';
00153     }
00154     return s;
00155 }
00156 
00157 
00160 cv::Mat MarkerCode::getImg(unsigned int pixSize) const {
00161     const unsigned int borderSize = 1;
00162     unsigned int nrows = n() + 2 * borderSize;
00163     if (pixSize % nrows != 0)
00164         pixSize = pixSize + nrows - pixSize % nrows;
00165     unsigned int cellSize = pixSize / nrows;
00166     cv::Mat img(pixSize, pixSize, CV_8U, cv::Scalar::all(0)); // create black image (init image to 0s)
00167     // double for to go over all the cells
00168     for (unsigned int i = 0; i < n(); i++) {
00169         for (unsigned int j = 0; j < n(); j++) {
00170             if (_bits[0][i * n() + j] != 0) { // just draw if it is 1, since the image has been init to 0
00171                                               // double for to go over all the pixels in the cell
00172                 for (unsigned int k = 0; k < cellSize; k++) {
00173                     for (unsigned int l = 0; l < cellSize; l++) {
00174                         img.at< uchar >((i + borderSize) * cellSize + k, (j + borderSize) * cellSize + l) = 255;
00175                     }
00176                 }
00177             }
00178         }
00179     }
00180     return img;
00181 }
00182 
00183 
00186 unsigned int MarkerCode::hammingDistance(const std::vector< bool > &m1, const std::vector< bool > &m2) const {
00187     unsigned int res = 0;
00188     for (unsigned int i = 0; i < m1.size(); i++)
00189         if (m1[i] != m2[i])
00190             res++;
00191     return res;
00192 }
00193 
00194 
00195 
00196 
00199 bool Dictionary::fromFile(std::string filename) {
00200     cv::FileStorage fs(filename, cv::FileStorage::READ);
00201     int nmarkers, markersize;
00202 
00203     // read number of markers
00204     fs["nmarkers"] >> nmarkers;                     // cardinal of D
00205     fs["markersize"] >> markersize;                 // n
00206     fs["tau0"] >> tau0;
00207 
00208     // read each marker info
00209     for (int i = 0; i < nmarkers; i++) {
00210         std::string s;
00211         fs["marker_" + toStr(i)] >> s;
00212         MarkerCode m(markersize);
00213         m.fromString(s);
00214         push_back(m);
00215     }
00216     fs.release();
00217     return true;
00218 };
00219 
00222 bool Dictionary::toFile(std::string filename) {
00223     cv::FileStorage fs(filename, cv::FileStorage::WRITE);
00224     // save number of markers
00225     fs << "nmarkers" << (int)size();                               // cardinal of D
00226     fs << "markersize" << (int)((*this)[0].n());                   // n
00227     fs << "tau0" << (int)(this->tau0); // n
00228     // save each marker code
00229     for (unsigned int i = 0; i < size(); i++) {
00230         std::string s = ((*this)[i]).toString();
00231         fs << "marker_" + toStr(i) << s;
00232     }
00233     fs.release();
00234     return true;
00235 };
00236 
00239 unsigned int Dictionary::distance(const MarkerCode &m, unsigned int &minMarker, unsigned int &minRot) {
00240     unsigned int res = m.size();
00241     for (unsigned int i = 0; i < size(); i++) {
00242         unsigned int minRotAux;
00243         unsigned int distance = (*this)[i].distance(m, minRotAux);
00244         if (distance < res) {
00245             minMarker = i;
00246             minRot = minRotAux;
00247             res = distance;
00248         }
00249     }
00250     return res;
00251 }
00252 
00253 
00256 unsigned int Dictionary::minimunDistance() {
00257     if (size() == 0)
00258         return 0;
00259     unsigned int minDist = (*this)[0].size();
00260     // for each marker in D
00261     for (unsigned int i = 0; i < size(); i++) {
00262         // calculate self distance of the marker
00263         minDist = std::min(minDist, (*this)[i].selfDistance());
00264 
00265         // calculate distance to all the following markers
00266         for (unsigned int j = i + 1; j < size(); j++) {
00267             minDist = std::min(minDist, (*this)[i].distance((*this)[j]));
00268         }
00269     }
00270     return minDist;
00271 }
00272 
00273 
00274 
00275 
00278 bool HighlyReliableMarkers::loadDictionary(Dictionary D, float correctionDistanceRate) {
00279     if (D.size() == 0)
00280         return false;
00281     _D = D;
00282     _n = _D[0].n();
00283     _ncellsBorder = (_D[0].n() + 2);
00284     _correctionDistance = correctionDistanceRate * ((D.tau0-1)/2);
00285     cerr << "aruco :: _correctionDistance = " << _correctionDistance << endl;
00286     _binaryTree.loadDictionary(&D);
00287     return true;
00288 }
00289 
00290 bool HighlyReliableMarkers::loadDictionary(std::string filename, float correctionDistance) {
00291     Dictionary D;
00292     D.fromFile(filename);
00293     return loadDictionary(D, correctionDistance);
00294 }
00295 
00296 
00299 int HighlyReliableMarkers::detect(const cv::Mat &in, int &nRotations) {
00300 
00301     assert(in.rows == in.cols);
00302     cv::Mat grey;
00303     if (in.type() == CV_8UC1)
00304         grey = in;
00305     else
00306         cv::cvtColor(in, grey, CV_BGR2GRAY);
00307     // threshold image
00308     cv::threshold(grey, grey, 125, 255, cv::THRESH_BINARY | cv::THRESH_OTSU);
00309     _swidth = grey.rows / _ncellsBorder;
00310 
00311     // check borders, even not necesary for the highly reliable markers
00312     // if(!checkBorders(grey)) return -1;
00313 
00314     // obtain inner code
00315     MarkerCode candidate = getMarkerCode(grey);
00316 
00317     // search each marker id in the balanced binary tree
00318     unsigned int orgPos;
00319     for (unsigned int i = 0; i < 4; i++) {
00320         if (_binaryTree.findId(candidate.getId(i), orgPos)) {
00321             nRotations = i;
00322             // return candidate.getId(i);
00323             return orgPos;
00324         }
00325     }
00326 
00327     // alternative version without using the balanced binary tree (less eficient)
00328     //         for(uint i=0; i<_D.size(); i++) {
00329     //           for(uint j=0; j<4; j++) {
00330     //        if(_D[i].getId() == candidate.getId(j)) {
00331     //          nRotations = j;
00332     //          //return candidate.getId(j);
00333     //          return i;
00334     //        }
00335     //           }
00336     //         }
00337 
00338     // correct errors
00339     unsigned int minMarker, minRot;
00340     if (_D.distance(candidate, minMarker, minRot) <= _correctionDistance) {
00341         nRotations = minRot;
00342         return minMarker;
00343         // return _D[minMarker].getId();
00344     }
00345 
00346     return -1;
00347 }
00348 
00349 
00352 bool HighlyReliableMarkers::checkBorders(cv::Mat grey) {
00353     for (int y = 0; y < _ncellsBorder; y++) {
00354         int inc = _ncellsBorder - 1;
00355         if (y == 0 || y == _ncellsBorder - 1)
00356             inc = 1; // for first and last row, check the whole border
00357         for (int x = 0; x < _ncellsBorder; x += inc) {
00358             int Xstart = (x) * (_swidth);
00359             int Ystart = (y) * (_swidth);
00360             cv::Mat square = grey(cv::Rect(Xstart, Ystart, _swidth, _swidth));
00361             int nZ = cv::countNonZero(square);
00362             if (nZ > (_swidth * _swidth) / 2) {
00363                 return false; // can not be a marker because the border element is not black!
00364             }
00365         }
00366     }
00367     return true;
00368 }
00369 
00372 MarkerCode HighlyReliableMarkers::getMarkerCode(const cv::Mat &grey) {
00373     MarkerCode candidate(_n);
00374     for (int y = 0; y < _n; y++) {
00375         for (int x = 0; x < _n; x++) {
00376             int Xstart = (x + 1) * (_swidth);
00377             int Ystart = (y + 1) * (_swidth);
00378             cv::Mat square = grey(cv::Rect(Xstart, Ystart, _swidth, _swidth));
00379             int nZ = countNonZero(square);
00380             if (nZ > (_swidth * _swidth) / 2)
00381                 candidate.set(y * _n + x, 1);
00382         }
00383     }
00384     return candidate;
00385 }
00386 
00387 
00388 
00391 void HighlyReliableMarkers::BalancedBinaryTree::loadDictionary(Dictionary *D) {
00392     // create _orderD wich is a sorted version of D
00393     _orderD.clear();
00394     for (unsigned int i = 0; i < D->size(); i++) {
00395         _orderD.push_back(std::pair< unsigned int, unsigned int >((*D)[i].getId(), i));
00396     }
00397     std::sort(_orderD.begin(), _orderD.end());
00398 
00399     // calculate the number of levels of the tree
00400     unsigned int levels = 0;
00401     while (pow(float(2), float(levels)) <= _orderD.size())
00402         levels++;
00403     //       levels-=1; // only count full levels
00404 
00405     // auxiliar vector to know which elements are already in the tree
00406     std::vector< bool > visited;
00407     visited.resize(_orderD.size(), false);
00408 
00409     // calculate position of the root element
00410     unsigned int rootIdx = _orderD.size() / 2;
00411     visited[rootIdx] = true; // mark it as visited
00412     _root = rootIdx;
00413 
00414     //    for(int i=0; i<visited.size(); i++) std::cout << visited[i] << std::endl;
00415 
00416     // auxiliar vector to store the ids intervals (max and min) during the creation of the tree
00417     std::vector< std::pair< unsigned int, unsigned int > > intervals;
00418     // first, add the two intervals at each side of root element
00419     intervals.push_back(std::pair< unsigned int, unsigned int >(0, rootIdx));
00420     intervals.push_back(std::pair< unsigned int, unsigned int >(rootIdx, _orderD.size()));
00421 
00422     // init the tree
00423     _binaryTree.clear();
00424     _binaryTree.resize(_orderD.size());
00425 
00426     // add root information to the tree (make sure child do not coincide with self root for small sizes of D)
00427     if (!visited[(0 + rootIdx) / 2])
00428         _binaryTree[rootIdx].first = (0 + rootIdx) / 2;
00429     else
00430         _binaryTree[rootIdx].first = -1;
00431     if (!visited[(rootIdx + _orderD.size()) / 2])
00432         _binaryTree[rootIdx].second = (rootIdx + _orderD.size()) / 2;
00433     else
00434         _binaryTree[rootIdx].second = -1;
00435 
00436     // for each tree level
00437     for (unsigned int i = 1; i < levels; i++) {
00438         unsigned int nintervals = intervals.size(); // count number of intervals and process them
00439         for (unsigned int j = 0; j < nintervals; j++) {
00440             // store interval information and delete it
00441             unsigned int lowerBound, higherBound;
00442             lowerBound = intervals.back().first;
00443             higherBound = intervals.back().second;
00444             intervals.pop_back();
00445 
00446             // center of the interval
00447             unsigned int center = (higherBound + lowerBound) / 2;
00448 
00449             // if center not visited, continue
00450             if (!visited[center])
00451                 visited[center] = true;
00452             else
00453                 continue;
00454 
00455             // calculate centers of the child intervals
00456             unsigned int lowerChild = (lowerBound + center) / 2;
00457             unsigned int higherChild = (center + higherBound) / 2;
00458 
00459             // if not visited (lower child)
00460             if (!visited[lowerChild]) {
00461                 intervals.insert(intervals.begin(), std::pair< unsigned int, unsigned int >(lowerBound, center)); // add the interval to analyze later
00462                 _binaryTree[center].first = lowerChild;                                                           // add as a child in the tree
00463             } else
00464                 _binaryTree[center].first = -1; // if not, mark as no child
00465 
00466             // (higher child, same as lower child)
00467             if (!visited[higherChild]) {
00468                 intervals.insert(intervals.begin(), std::pair< unsigned int, unsigned int >(center, higherBound));
00469                 _binaryTree[center].second = higherChild;
00470             } else
00471                 _binaryTree[center].second = -1;
00472         }
00473     }
00474 
00475     // print tree
00476     //     for(uint i=0; i<_binaryTree.size(); i++) std::cout << _binaryTree[i].first << " " << _binaryTree[i].second << std::endl;
00477     //     std::cout << std::endl;
00478 }
00479 
00480 
00481 int count = 0;
00482 int idc = 11;
00483 
00486 bool HighlyReliableMarkers::BalancedBinaryTree::findId(unsigned int id, unsigned int &orgPos) {
00487     int pos = _root;                             // first position is root
00488     while (pos != -1) {                          // while having a valid position
00489         unsigned int posId = _orderD[pos].first; // calculate id of the node
00490         if (posId == id) {
00491             orgPos = _orderD[pos].second;
00492             return true; // if is the desire id, return true
00493         } else if (posId < id)
00494             pos = _binaryTree[pos].second; // if desired id is higher, look in higher child
00495         else
00496             pos = _binaryTree[pos].first; // if it is lower, look in lower child
00497     }
00498     count++;
00499     return false; // if nothing found, return false
00500 }
00501 }


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