Orb.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00037 #include <rtabmap/core/Features2d.h>
00038 #include <rtabmap/utilite/UConversion.h>
00039 #include <rtabmap/utilite/UStl.h>
00040 
00041 #include "opencv2/features2d/features2d.hpp"
00042 #include "opencv2/imgproc/imgproc.hpp"
00043 #include "opencv2/imgproc/imgproc_c.h"
00044 #include <algorithm>
00045 #include <iterator>
00046 
00047 #include "Orb.h"
00049 
00050 using namespace cv;
00051 
00052 namespace rtabmap
00053 {
00054 
00055 const float HARRIS_K = 0.04f;
00056 
00061 static void
00062 HarrisResponses(const Mat& img, std::vector<KeyPoint>& pts, int blockSize, float harris_k)
00063 {
00064     CV_Assert( img.type() == CV_8UC1 && blockSize*blockSize <= 2048 );
00065 
00066     size_t ptidx, ptsize = pts.size();
00067 
00068     const uchar* ptr00 = img.ptr<uchar>();
00069     int step = (int)(img.step/img.elemSize1());
00070     int r = blockSize/2;
00071 
00072     float scale = (1 << 2) * blockSize * 255.0f;
00073     scale = 1.0f / scale;
00074     float scale_sq_sq = scale * scale * scale * scale;
00075 
00076     AutoBuffer<int> ofsbuf(blockSize*blockSize);
00077     int* ofs = ofsbuf;
00078     for( int i = 0; i < blockSize; i++ )
00079         for( int j = 0; j < blockSize; j++ )
00080             ofs[i*blockSize + j] = (int)(i*step + j);
00081 
00082     for( ptidx = 0; ptidx < ptsize; ptidx++ )
00083     {
00084         int x0 = cvRound(pts[ptidx].pt.x - r);
00085         int y0 = cvRound(pts[ptidx].pt.y - r);
00086 
00087         const uchar* ptr0 = ptr00 + y0*step + x0;
00088         int a = 0, b = 0, c = 0;
00089 
00090         for( int k = 0; k < blockSize*blockSize; k++ )
00091         {
00092             const uchar* ptr = ptr0 + ofs[k];
00093             int Ix = (ptr[1] - ptr[-1])*2 + (ptr[-step+1] - ptr[-step-1]) + (ptr[step+1] - ptr[step-1]);
00094             int Iy = (ptr[step] - ptr[-step])*2 + (ptr[step-1] - ptr[-step-1]) + (ptr[step+1] - ptr[-step+1]);
00095             a += Ix*Ix;
00096             b += Iy*Iy;
00097             c += Ix*Iy;
00098         }
00099         pts[ptidx].response = ((float)a * b - (float)c * c -
00100                                harris_k * ((float)a + b) * ((float)a + b))*scale_sq_sq;
00101     }
00102 }
00103 
00105 
00106 static float IC_Angle(const Mat& image, const int half_k, Point2f pt,
00107                       const std::vector<int> & u_max)
00108 {
00109     int m_01 = 0, m_10 = 0;
00110 
00111     const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));
00112 
00113     // Treat the center line differently, v=0
00114     for (int u = -half_k; u <= half_k; ++u)
00115         m_10 += u * center[u];
00116 
00117     // Go line by line in the circular patch
00118     int step = (int)image.step1();
00119     for (int v = 1; v <= half_k; ++v)
00120     {
00121         // Proceed over the two lines
00122         int v_sum = 0;
00123         int d = u_max[v];
00124         for (int u = -d; u <= d; ++u)
00125         {
00126             int val_plus = center[u + v*step], val_minus = center[u - v*step];
00127             v_sum += (val_plus - val_minus);
00128             m_10 += u * (val_plus + val_minus);
00129         }
00130         m_01 += v * v_sum;
00131     }
00132 
00133     return fastAtan2((float)m_01, (float)m_10);
00134 }
00135 
00137 
00138 static void computeOrbDescriptor(const KeyPoint& kpt,
00139                                  const Mat& img, const Point* pattern,
00140                                  uchar* desc, int dsize, int WTA_K)
00141 {
00142     float angle = kpt.angle;
00143     //angle = cvFloor(angle/12)*12.f;
00144     angle *= (float)(CV_PI/180.f);
00145     float a = (float)cos(angle), b = (float)sin(angle);
00146 
00147     const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
00148     int step = (int)img.step;
00149 
00150     float x, y;
00151     int ix, iy;
00152 #if 1
00153     #define GET_VALUE(idx) \
00154            (x = pattern[idx].x*a - pattern[idx].y*b, \
00155             y = pattern[idx].x*b + pattern[idx].y*a, \
00156             ix = cvRound(x), \
00157             iy = cvRound(y), \
00158             *(center + iy*step + ix) )
00159 #else
00160     #define GET_VALUE(idx) \
00161         (x = pattern[idx].x*a - pattern[idx].y*b, \
00162         y = pattern[idx].x*b + pattern[idx].y*a, \
00163         ix = cvFloor(x), iy = cvFloor(y), \
00164         x -= ix, y -= iy, \
00165         cvRound(center[iy*step + ix]*(1-x)*(1-y) + center[(iy+1)*step + ix]*(1-x)*y + \
00166                 center[iy*step + ix+1]*x*(1-y) + center[(iy+1)*step + ix+1]*x*y))
00167 #endif
00168 
00169     if( WTA_K == 2 )
00170     {
00171         for (int i = 0; i < dsize; ++i, pattern += 16)
00172         {
00173             int t0, t1, val;
00174             t0 = GET_VALUE(0); t1 = GET_VALUE(1);
00175             val = t0 < t1;
00176             t0 = GET_VALUE(2); t1 = GET_VALUE(3);
00177             val |= (t0 < t1) << 1;
00178             t0 = GET_VALUE(4); t1 = GET_VALUE(5);
00179             val |= (t0 < t1) << 2;
00180             t0 = GET_VALUE(6); t1 = GET_VALUE(7);
00181             val |= (t0 < t1) << 3;
00182             t0 = GET_VALUE(8); t1 = GET_VALUE(9);
00183             val |= (t0 < t1) << 4;
00184             t0 = GET_VALUE(10); t1 = GET_VALUE(11);
00185             val |= (t0 < t1) << 5;
00186             t0 = GET_VALUE(12); t1 = GET_VALUE(13);
00187             val |= (t0 < t1) << 6;
00188             t0 = GET_VALUE(14); t1 = GET_VALUE(15);
00189             val |= (t0 < t1) << 7;
00190 
00191             desc[i] = (uchar)val;
00192         }
00193     }
00194     else if( WTA_K == 3 )
00195     {
00196         for (int i = 0; i < dsize; ++i, pattern += 12)
00197         {
00198             int t0, t1, t2, val;
00199             t0 = GET_VALUE(0); t1 = GET_VALUE(1); t2 = GET_VALUE(2);
00200             val = t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0);
00201 
00202             t0 = GET_VALUE(3); t1 = GET_VALUE(4); t2 = GET_VALUE(5);
00203             val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 2;
00204 
00205             t0 = GET_VALUE(6); t1 = GET_VALUE(7); t2 = GET_VALUE(8);
00206             val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 4;
00207 
00208             t0 = GET_VALUE(9); t1 = GET_VALUE(10); t2 = GET_VALUE(11);
00209             val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 6;
00210 
00211             desc[i] = (uchar)val;
00212         }
00213     }
00214     else if( WTA_K == 4 )
00215     {
00216         for (int i = 0; i < dsize; ++i, pattern += 16)
00217         {
00218             int t0, t1, t2, t3, u, v, k, val;
00219             t0 = GET_VALUE(0); t1 = GET_VALUE(1);
00220             t2 = GET_VALUE(2); t3 = GET_VALUE(3);
00221             u = 0, v = 2;
00222             if( t1 > t0 ) t0 = t1, u = 1;
00223             if( t3 > t2 ) t2 = t3, v = 3;
00224             k = t0 > t2 ? u : v;
00225             val = k;
00226 
00227             t0 = GET_VALUE(4); t1 = GET_VALUE(5);
00228             t2 = GET_VALUE(6); t3 = GET_VALUE(7);
00229             u = 0, v = 2;
00230             if( t1 > t0 ) t0 = t1, u = 1;
00231             if( t3 > t2 ) t2 = t3, v = 3;
00232             k = t0 > t2 ? u : v;
00233             val |= k << 2;
00234 
00235             t0 = GET_VALUE(8); t1 = GET_VALUE(9);
00236             t2 = GET_VALUE(10); t3 = GET_VALUE(11);
00237             u = 0, v = 2;
00238             if( t1 > t0 ) t0 = t1, u = 1;
00239             if( t3 > t2 ) t2 = t3, v = 3;
00240             k = t0 > t2 ? u : v;
00241             val |= k << 4;
00242 
00243             t0 = GET_VALUE(12); t1 = GET_VALUE(13);
00244             t2 = GET_VALUE(14); t3 = GET_VALUE(15);
00245             u = 0, v = 2;
00246             if( t1 > t0 ) t0 = t1, u = 1;
00247             if( t3 > t2 ) t2 = t3, v = 3;
00248             k = t0 > t2 ? u : v;
00249             val |= k << 6;
00250 
00251             desc[i] = (uchar)val;
00252         }
00253     }
00254     else
00255         CV_Error( CV_StsBadSize, "Wrong WTA_K. It can be only 2, 3 or 4." );
00256 
00257     #undef GET_VALUE
00258 }
00259 
00260 
00261 static void initializeOrbPattern( const Point* pattern0, std::vector<Point>& pattern, int ntuples, int tupleSize, int poolSize )
00262 {
00263     RNG rng(0x12345678);
00264     int i, k, k1;
00265     pattern.resize(ntuples*tupleSize);
00266 
00267     for( i = 0; i < ntuples; i++ )
00268     {
00269         for( k = 0; k < tupleSize; k++ )
00270         {
00271             for(;;)
00272             {
00273                 int idx = rng.uniform(0, poolSize);
00274                 Point pt = pattern0[idx];
00275                 for( k1 = 0; k1 < k; k1++ )
00276                     if( pattern[tupleSize*i + k1] == pt )
00277                         break;
00278                 if( k1 == k )
00279                 {
00280                     pattern[tupleSize*i + k] = pt;
00281                     break;
00282                 }
00283             }
00284         }
00285     }
00286 }
00287 
00288 static int bit_pattern_31_[256*4] =
00289 {
00290     8,-3, 9,5/*mean (0), correlation (0)*/,
00291     4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
00292     -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
00293     7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
00294     2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
00295     1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
00296     -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
00297     -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
00298     -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
00299     10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
00300     -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
00301     -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
00302     7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
00303     -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
00304     -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
00305     -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
00306     12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
00307     -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
00308     -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
00309     11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/,
00310     4,7, 5,1/*mean (0.205106), correlation (0.186848)*/,
00311     5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/,
00312     3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/,
00313     -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/,
00314     -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/,
00315     -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/,
00316     -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/,
00317     -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/,
00318     -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/,
00319     5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/,
00320     5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/,
00321     1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/,
00322     9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/,
00323     4,7, 4,12/*mean (0.131005), correlation (0.257622)*/,
00324     2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/,
00325     -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/,
00326     -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/,
00327     4,11, 9,12/*mean (0.226226), correlation (0.258255)*/,
00328     0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/,
00329     -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/,
00330     -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/,
00331     -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/,
00332     8,12, 10,7/*mean (0.225337), correlation (0.282851)*/,
00333     0,9, 1,3/*mean (0.226687), correlation (0.278734)*/,
00334     7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/,
00335     -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/,
00336     10,7, 12,1/*mean (0.125517), correlation (0.31089)*/,
00337     -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/,
00338     10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/,
00339     -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/,
00340     -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/,
00341     3,3, 7,8/*mean (0.177755), correlation (0.309394)*/,
00342     5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/,
00343     -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/,
00344     3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/,
00345     2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/,
00346     -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/,
00347     -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/,
00348     -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/,
00349     -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/,
00350     6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/,
00351     -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/,
00352     -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/,
00353     -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/,
00354     3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/,
00355     -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/,
00356     -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/,
00357     2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/,
00358     -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/,
00359     -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/,
00360     5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/,
00361     -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/,
00362     -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/,
00363     -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/,
00364     10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/,
00365     7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/,
00366     -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/,
00367     -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/,
00368     7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/,
00369     -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/,
00370     -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/,
00371     -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/,
00372     7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/,
00373     -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/,
00374     1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/,
00375     2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/,
00376     -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/,
00377     -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/,
00378     7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/,
00379     1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/,
00380     9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/,
00381     -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/,
00382     -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/,
00383     7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/,
00384     12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/,
00385     6,3, 7,11/*mean (0.1074), correlation (0.413224)*/,
00386     5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/,
00387     2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/,
00388     3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/,
00389     2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/,
00390     9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/,
00391     -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/,
00392     -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/,
00393     1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/,
00394     6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/,
00395     2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/,
00396     6,3, 11,0/*mean (0.204588), correlation (0.411762)*/,
00397     3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/,
00398     7,8, 9,3/*mean (0.213237), correlation (0.409306)*/,
00399     -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/,
00400     -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/,
00401     -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/,
00402     -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/,
00403     8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/,
00404     4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/,
00405     -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/,
00406     4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/,
00407     -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/,
00408     -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/,
00409     7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/,
00410     -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/,
00411     -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/,
00412     8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/,
00413     -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/,
00414     1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/,
00415     7,-4, 9,1/*mean (0.132692), correlation (0.454)*/,
00416     -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/,
00417     11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/,
00418     -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/,
00419     3,7, 7,12/*mean (0.147627), correlation (0.456643)*/,
00420     5,5, 10,8/*mean (0.152901), correlation (0.455036)*/,
00421     0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/,
00422     -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/,
00423     0,7, 2,12/*mean (0.18312), correlation (0.433855)*/,
00424     -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/,
00425     5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/,
00426     3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/,
00427     -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/,
00428     -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/,
00429     -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/,
00430     6,5, 8,0/*mean (0.1972), correlation (0.450481)*/,
00431     -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/,
00432     -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/,
00433     1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/,
00434     4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/,
00435     -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/,
00436     2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/,
00437     -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/,
00438     4,1, 9,3/*mean (0.23962), correlation (0.444824)*/,
00439     -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/,
00440     -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/,
00441     7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/,
00442     4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/,
00443     -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/,
00444     7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/,
00445     7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/,
00446     -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/,
00447     -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/,
00448     -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/,
00449     2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/,
00450     10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/,
00451     -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/,
00452     8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/,
00453     2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/,
00454     -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/,
00455     -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/,
00456     -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/,
00457     5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/,
00458     -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/,
00459     -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/,
00460     -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/,
00461     -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/,
00462     -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/,
00463     2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/,
00464     -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/,
00465     -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/,
00466     -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/,
00467     -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/,
00468     6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/,
00469     -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/,
00470     11,11, 12,6/*mean (0.16652), correlation (0.497632)*/,
00471     7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/,
00472     -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/,
00473     -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/,
00474     -7,1, -6,7/*mean (0.175), correlation (0.500024)*/,
00475     -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/,
00476     -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/,
00477     -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/,
00478     -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/,
00479     -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/,
00480     1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/,
00481     1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/,
00482     9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/,
00483     5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/,
00484     -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/,
00485     -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/,
00486     -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/,
00487     -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/,
00488     8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/,
00489     2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/,
00490     7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/,
00491     -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/,
00492     -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/,
00493     4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/,
00494     3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/,
00495     -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/,
00496     5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/,
00497     4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/,
00498     -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/,
00499     0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/,
00500     -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/,
00501     3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/,
00502     -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/,
00503     8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/,
00504     -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/,
00505     2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/,
00506     10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/,
00507     6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/,
00508     -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/,
00509     -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/,
00510     -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/,
00511     -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/,
00512     -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/,
00513     4,2, 12,12/*mean (0.01778), correlation (0.546921)*/,
00514     2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/,
00515     6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/,
00516     3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/,
00517     11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/,
00518     -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/,
00519     4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/,
00520     2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/,
00521     -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/,
00522     -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/,
00523     -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/,
00524     6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/,
00525     0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/,
00526     -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/,
00527     -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/,
00528     -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/,
00529     5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/,
00530     2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/,
00531     -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/,
00532     9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/,
00533     11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/,
00534     3,0, 3,5/*mean (0.101147), correlation (0.525576)*/,
00535     -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/,
00536     3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/,
00537     -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/,
00538     5,8, 12,11/*mean (0.114181), correlation (0.555793)*/,
00539     8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/,
00540     7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/,
00541     -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/,
00542     7,3, 12,4/*mean (0.122582), correlation (0.555825)*/,
00543     9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/,
00544     7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/,
00545     -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/
00546 };
00547 
00548 
00549 static void makeRandomPattern(int patchSize, Point* pattern, int npoints)
00550 {
00551     RNG rng(0x34985739); // we always start with a fixed seed,
00552                          // to make patterns the same on each run
00553     for( int i = 0; i < npoints; i++ )
00554     {
00555         pattern[i].x = rng.uniform(-patchSize/2, patchSize/2+1);
00556         pattern[i].y = rng.uniform(-patchSize/2, patchSize/2+1);
00557     }
00558 }
00559 
00560 
00561 static inline float getScale(int level, int firstLevel, double scaleFactor)
00562 {
00563     return (float)std::pow(scaleFactor, (double)(level - firstLevel));
00564 }
00565 
00569 CV_ORB::CV_ORB(int _nfeatures, float _scaleFactor, int _nlevels, int _edgeThreshold,
00570          int _firstLevel, int _WTA_K, int _scoreType, int _patchSize, const ParametersMap & _fastParameters) :
00571     nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
00572     edgeThreshold(_edgeThreshold), firstLevel(_firstLevel), WTA_K(_WTA_K),
00573     scoreType(_scoreType), patchSize(_patchSize), fastParameters(_fastParameters)
00574 {}
00575 
00576 
00577 int CV_ORB::descriptorSize() const
00578 {
00579     return kBytes;
00580 }
00581 
00582 int CV_ORB::descriptorType() const
00583 {
00584     return CV_8U;
00585 }
00586 
00592 void CV_ORB::operator()(InputArray image, InputArray mask, std::vector<KeyPoint>& keypoints) const
00593 {
00594     (*this)(image, mask, keypoints, noArray(), false);
00595 }
00596 
00597 
00604 static void computeOrientation(const Mat& image, std::vector<KeyPoint>& keypoints,
00605                                int halfPatchSize, const std::vector<int>& umax)
00606 {
00607     // Process each keypoint
00608     for (std::vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00609          keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00610     {
00611         keypoint->angle = IC_Angle(image, halfPatchSize, keypoint->pt, umax);
00612     }
00613 }
00614 
00615 
00621 static void computeKeyPoints(const std::vector<Mat>& imagePyramid,
00622                              const std::vector<Mat>& maskPyramid,
00623                              std::vector<std::vector<KeyPoint> >& allKeypoints,
00624                              int nfeatures, int firstLevel, double scaleFactor,
00625                              int edgeThreshold, int patchSize, int scoreType,
00626                                                          ParametersMap fastParameters)
00627 {
00628     int nlevels = (int)imagePyramid.size();
00629     std::vector<int> nfeaturesPerLevel(nlevels);
00630 
00631     // fill the extractors and descriptors for the corresponding scales
00632     float factor = (float)(1.0 / scaleFactor);
00633     float ndesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
00634 
00635     int sumFeatures = 0;
00636     for( int level = 0; level < nlevels-1; level++ )
00637     {
00638         nfeaturesPerLevel[level] = cvRound(ndesiredFeaturesPerScale);
00639         sumFeatures += nfeaturesPerLevel[level];
00640         ndesiredFeaturesPerScale *= factor;
00641     }
00642     nfeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
00643 
00644     // Make sure we forget about what is too close to the boundary
00645     //edge_threshold_ = std::max(edge_threshold_, patch_size_/2 + kKernelWidth / 2 + 2);
00646 
00647     // pre-compute the end of a row in a circular patch
00648     int halfPatchSize = patchSize / 2;
00649     std::vector<int> umax(halfPatchSize + 2);
00650 
00651     int v, v0, vmax = cvFloor(halfPatchSize * sqrt(2.f) / 2 + 1);
00652     int vmin = cvCeil(halfPatchSize * sqrt(2.f) / 2);
00653     for (v = 0; v <= vmax; ++v)
00654         umax[v] = cvRound(sqrt((double)halfPatchSize * halfPatchSize - v * v));
00655 
00656     // Make sure we are symmetric
00657     for (v = halfPatchSize, v0 = 0; v >= vmin; --v)
00658     {
00659         while (umax[v0] == umax[v0 + 1])
00660             ++v0;
00661         umax[v] = v0;
00662         ++v0;
00663     }
00664 
00665     allKeypoints.resize(nlevels);
00666 
00667     for (int level = 0; level < nlevels; ++level)
00668     {
00669         int featuresNum = nfeaturesPerLevel[level];
00670         allKeypoints[level].reserve(featuresNum*2);
00671 
00672         std::vector<KeyPoint> & keypoints = allKeypoints[level];
00673 
00674         // Detect FAST features, maxFeatures is used by the GridAdaptor of FAST
00675         uInsert(fastParameters, ParametersPair(Parameters::kKpMaxFeatures(), uNumber2Str(scoreType == CV_ORB::HARRIS_SCORE?2*featuresNum:featuresNum)));
00676         FAST fast(fastParameters);
00677         keypoints = fast.generateKeypoints(imagePyramid[level], maskPyramid[level]);
00678 
00679         // Remove keypoints very close to the border
00680         KeyPointsFilter::runByImageBorder(keypoints, imagePyramid[level].size(), edgeThreshold);
00681 
00682         if( scoreType == CV_ORB::HARRIS_SCORE )
00683         {
00684             // Keep more points than necessary as FAST does not give amazing corners
00685             KeyPointsFilter::retainBest(keypoints, 2 * featuresNum);
00686 
00687             // Compute the Harris cornerness (better scoring than FAST)
00688             HarrisResponses(imagePyramid[level], keypoints, 7, HARRIS_K);
00689         }
00690 
00691         //cull to the final desired level, using the new Harris scores or the original FAST scores.
00692         KeyPointsFilter::retainBest(keypoints, featuresNum);
00693 
00694         float sf = getScale(level, firstLevel, scaleFactor);
00695 
00696         // Set the level of the coordinates
00697         for (std::vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00698              keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00699         {
00700             keypoint->octave = level;
00701             keypoint->size = patchSize*sf;
00702         }
00703 
00704         computeOrientation(imagePyramid[level], keypoints, halfPatchSize, umax);
00705     }
00706 }
00707 
00708 
00716 static void computeDescriptors(const Mat& image, std::vector<KeyPoint>& keypoints, Mat& descriptors,
00717                                const std::vector<Point>& pattern, int dsize, int WTA_K)
00718 {
00719     //convert to grayscale if more than one color
00720     CV_Assert(image.type() == CV_8UC1);
00721     //create the descriptor mat, keypoints.size() rows, BYTES cols
00722     descriptors = Mat::zeros((int)keypoints.size(), dsize, CV_8UC1);
00723 
00724     for (size_t i = 0; i < keypoints.size(); i++)
00725         computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i), dsize, WTA_K);
00726 }
00727 
00728 
00737 void CV_ORB::operator()( InputArray _image, InputArray _mask, std::vector<KeyPoint>& _keypoints,
00738                       OutputArray _descriptors, bool useProvidedKeypoints) const
00739 {
00740     CV_Assert(patchSize >= 2);
00741 
00742     bool do_keypoints = !useProvidedKeypoints;
00743     bool do_descriptors = _descriptors.needed();
00744 
00745     if( (!do_keypoints && !do_descriptors) || _image.empty() )
00746         return;
00747 
00748     //ROI handling
00749     const int HARRIS_BLOCK_SIZE = 9;
00750     int halfPatchSize = patchSize / 2;
00751     int border = std::max(edgeThreshold, std::max(halfPatchSize, HARRIS_BLOCK_SIZE/2))+1;
00752 
00753     Mat image = _image.getMat(), mask = _mask.getMat();
00754     if( image.type() != CV_8UC1 )
00755         cvtColor(_image, image, CV_BGR2GRAY);
00756 
00757     int levelsNum = this->nlevels;
00758 
00759     if( !do_keypoints )
00760     {
00761         // if we have pre-computed keypoints, they may use more levels than it is set in parameters
00762         // !!!TODO!!! implement more correct method, independent from the used keypoint detector.
00763         // Namely, the detector should provide correct size of each keypoint. Based on the keypoint size
00764         // and the algorithm used (i.e. BRIEF, running on 31x31 patches) we should compute the approximate
00765         // scale-factor that we need to apply. Then we should cluster all the computed scale-factors and
00766         // for each cluster compute the corresponding image.
00767         //
00768         // In short, ultimately the descriptor should
00769         // ignore octave parameter and deal only with the keypoint size.
00770         levelsNum = 0;
00771         for( size_t i = 0; i < _keypoints.size(); i++ )
00772             levelsNum = std::max(levelsNum, std::max(_keypoints[i].octave, 0));
00773         levelsNum++;
00774     }
00775 
00776     // Pre-compute the scale pyramids
00777     std::vector<Mat> imagePyramid(levelsNum), maskPyramid(levelsNum);
00778     for (int level = 0; level < levelsNum; ++level)
00779     {
00780         float scale = 1/getScale(level, firstLevel, scaleFactor);
00781         Size sz(cvRound(image.cols*scale), cvRound(image.rows*scale));
00782         Size wholeSize(sz.width + border*2, sz.height + border*2);
00783         Mat temp(wholeSize, image.type()), masktemp;
00784         imagePyramid[level] = temp(Rect(border, border, sz.width, sz.height));
00785 
00786         if( !mask.empty() )
00787         {
00788             masktemp = Mat(wholeSize, mask.type());
00789             maskPyramid[level] = masktemp(Rect(border, border, sz.width, sz.height));
00790         }
00791 
00792         // Compute the resized image
00793         if( level != firstLevel )
00794         {
00795             if( level < firstLevel )
00796             {
00797                 resize(image, imagePyramid[level], sz, 0, 0, INTER_LINEAR);
00798                 if (!mask.empty())
00799                     resize(mask, maskPyramid[level], sz, 0, 0, INTER_LINEAR);
00800             }
00801             else
00802             {
00803                 resize(imagePyramid[level-1], imagePyramid[level], sz, 0, 0, INTER_LINEAR);
00804                 if (!mask.empty())
00805                 {
00806                     resize(maskPyramid[level-1], maskPyramid[level], sz, 0, 0, INTER_LINEAR);
00807                     threshold(maskPyramid[level], maskPyramid[level], 254, 0, THRESH_TOZERO);
00808                 }
00809             }
00810 
00811             copyMakeBorder(imagePyramid[level], temp, border, border, border, border,
00812                            BORDER_REFLECT_101+BORDER_ISOLATED);
00813             if (!mask.empty())
00814                 copyMakeBorder(maskPyramid[level], masktemp, border, border, border, border,
00815                                BORDER_CONSTANT+BORDER_ISOLATED);
00816         }
00817         else
00818         {
00819             copyMakeBorder(image, temp, border, border, border, border,
00820                            BORDER_REFLECT_101);
00821             if( !mask.empty() )
00822                 copyMakeBorder(mask, masktemp, border, border, border, border,
00823                                BORDER_CONSTANT+BORDER_ISOLATED);
00824         }
00825     }
00826 
00827     // Pre-compute the keypoints (we keep the best over all scales, so this has to be done beforehand
00828     std::vector < std::vector<KeyPoint> > allKeypoints;
00829     if( do_keypoints )
00830     {
00831         // Get keypoints, those will be far enough from the border that no check will be required for the descriptor
00832         computeKeyPoints(imagePyramid, maskPyramid, allKeypoints,
00833                          nfeatures, firstLevel, scaleFactor,
00834                          edgeThreshold, patchSize, scoreType,
00835                                                  fastParameters);
00836 
00837         // make sure we have the right number of keypoints keypoints
00838         /*vector<KeyPoint> temp;
00839 
00840         for (int level = 0; level < n_levels; ++level)
00841         {
00842             vector<KeyPoint>& keypoints = all_keypoints[level];
00843             temp.insert(temp.end(), keypoints.begin(), keypoints.end());
00844             keypoints.clear();
00845         }
00846 
00847         KeyPoint::retainBest(temp, n_features_);
00848 
00849         for (vector<KeyPoint>::iterator keypoint = temp.begin(),
00850              keypoint_end = temp.end(); keypoint != keypoint_end; ++keypoint)
00851             all_keypoints[keypoint->octave].push_back(*keypoint);*/
00852     }
00853     else
00854     {
00855         // Remove keypoints very close to the border
00856         KeyPointsFilter::runByImageBorder(_keypoints, image.size(), edgeThreshold);
00857 
00858         // Cluster the input keypoints depending on the level they were computed at
00859         allKeypoints.resize(levelsNum);
00860         for (std::vector<KeyPoint>::iterator keypoint = _keypoints.begin(),
00861              keypointEnd = _keypoints.end(); keypoint != keypointEnd; ++keypoint)
00862             allKeypoints[keypoint->octave].push_back(*keypoint);
00863 
00864         // Make sure we rescale the coordinates
00865         for (int level = 0; level < levelsNum; ++level)
00866         {
00867             if (level == firstLevel)
00868                 continue;
00869 
00870             std::vector<KeyPoint> & keypoints = allKeypoints[level];
00871             float scale = 1/getScale(level, firstLevel, scaleFactor);
00872             for (std::vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00873                  keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00874                 keypoint->pt *= scale;
00875         }
00876     }
00877 
00878     Mat descriptors;
00879     std::vector<Point> pattern;
00880 
00881     if( do_descriptors )
00882     {
00883         int nkeypoints = 0;
00884         for (int level = 0; level < levelsNum; ++level)
00885             nkeypoints += (int)allKeypoints[level].size();
00886         if( nkeypoints == 0 )
00887             _descriptors.release();
00888         else
00889         {
00890             _descriptors.create(nkeypoints, descriptorSize(), CV_8U);
00891             descriptors = _descriptors.getMat();
00892         }
00893 
00894         const int npoints = 512;
00895         Point patternbuf[npoints];
00896         const Point* pattern0 = (const Point*)bit_pattern_31_;
00897 
00898         if( patchSize != 31 )
00899         {
00900             pattern0 = patternbuf;
00901             makeRandomPattern(patchSize, patternbuf, npoints);
00902         }
00903 
00904         CV_Assert( WTA_K == 2 || WTA_K == 3 || WTA_K == 4 );
00905 
00906         if( WTA_K == 2 )
00907             std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
00908         else
00909         {
00910             int ntuples = descriptorSize()*4;
00911             initializeOrbPattern(pattern0, pattern, ntuples, WTA_K, npoints);
00912         }
00913     }
00914 
00915     _keypoints.clear();
00916     int offset = 0;
00917     for (int level = 0; level < levelsNum; ++level)
00918     {
00919         // Get the features and compute their orientation
00920         std::vector<KeyPoint>& keypoints = allKeypoints[level];
00921         int nkeypoints = (int)keypoints.size();
00922 
00923         // Compute the descriptors
00924         if (do_descriptors)
00925         {
00926             Mat desc;
00927             if (!descriptors.empty())
00928             {
00929                 desc = descriptors.rowRange(offset, offset + nkeypoints);
00930             }
00931 
00932             offset += nkeypoints;
00933             // preprocess the resized image
00934             Mat& workingMat = imagePyramid[level];
00935             //boxFilter(working_mat, working_mat, working_mat.depth(), Size(5,5), Point(-1,-1), true, BORDER_REFLECT_101);
00936             GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
00937             computeDescriptors(workingMat, keypoints, desc, pattern, descriptorSize(), WTA_K);
00938         }
00939 
00940         // Copy to the output data
00941         if (level != firstLevel)
00942         {
00943             float scale = getScale(level, firstLevel, scaleFactor);
00944             for (std::vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00945                  keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00946                 keypoint->pt *= scale;
00947         }
00948         // And add the keypoints to the output
00949         _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
00950     }
00951 }
00952 
00953 void CV_ORB::detectImpl( const Mat& image, std::vector<KeyPoint>& keypoints, const Mat& mask) const
00954 {
00955     (*this)(image, mask, keypoints, noArray(), false);
00956 }
00957 
00958 void CV_ORB::computeImpl( const Mat& image, std::vector<KeyPoint>& keypoints, Mat& descriptors) const
00959 {
00960     (*this)(image, Mat(), keypoints, descriptors, true);
00961 }
00962 
00963 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21