ORBextractor.cc 52 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. /**
  19. * Software License Agreement (BSD License)
  20. *
  21. * Copyright (c) 2009, Willow Garage, Inc.
  22. * All rights reserved.
  23. *
  24. * Redistribution and use in source and binary forms, with or without
  25. * modification, are permitted provided that the following conditions
  26. * are met:
  27. *
  28. * * Redistributions of source code must retain the above copyright
  29. * notice, this list of conditions and the following disclaimer.
  30. * * Redistributions in binary form must reproduce the above
  31. * copyright notice, this list of conditions and the following
  32. * disclaimer in the documentation and/or other materials provided
  33. * with the distribution.
  34. * * Neither the name of the Willow Garage nor the names of its
  35. * contributors may be used to endorse or promote products derived
  36. * from this software without specific prior written permission.
  37. *
  38. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  39. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  40. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  41. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  42. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  43. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  44. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  45. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  46. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  47. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  48. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  49. * POSSIBILITY OF SUCH DAMAGE.
  50. *
  51. */
  52. #include <opencv2/core/core.hpp>
  53. #include <opencv2/highgui/highgui.hpp>
  54. #include <opencv2/features2d/features2d.hpp>
  55. #include <opencv2/imgproc/imgproc.hpp>
  56. #include <vector>
  57. #include <iostream>
  58. #include "ORBextractor.h"
  59. using namespace cv;
  60. using namespace std;
  61. namespace ORB_SLAM3
  62. {
  63. const int PATCH_SIZE = 31;
  64. const int HALF_PATCH_SIZE = 15;
  65. const int EDGE_THRESHOLD = 19;
  66. static float IC_Angle(const Mat& image, Point2f pt, const vector<int> & u_max)
  67. {
  68. int m_01 = 0, m_10 = 0;
  69. const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));
  70. // Treat the center line differently, v=0
  71. for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
  72. m_10 += u * center[u];
  73. // Go line by line in the circuI853lar patch
  74. int step = (int)image.step1();
  75. for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
  76. {
  77. // Proceed over the two lines
  78. int v_sum = 0;
  79. int d = u_max[v];
  80. for (int u = -d; u <= d; ++u)
  81. {
  82. int val_plus = center[u + v*step], val_minus = center[u - v*step];
  83. v_sum += (val_plus - val_minus);
  84. m_10 += u * (val_plus + val_minus);
  85. }
  86. m_01 += v * v_sum;
  87. }
  88. return fastAtan2((float)m_01, (float)m_10);
  89. }
  90. const float factorPI = (float)(CV_PI/180.f);
  91. static void computeOrbDescriptor(const KeyPoint& kpt,
  92. const Mat& img, const Point* pattern,
  93. uchar* desc)
  94. {
  95. float angle = (float)kpt.angle*factorPI;
  96. float a = (float)cos(angle), b = (float)sin(angle);
  97. const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
  98. const int step = (int)img.step;
  99. #define GET_VALUE(idx) \
  100. center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
  101. cvRound(pattern[idx].x*a - pattern[idx].y*b)]
  102. for (int i = 0; i < 32; ++i, pattern += 16)
  103. {
  104. int t0, t1, val;
  105. t0 = GET_VALUE(0); t1 = GET_VALUE(1);
  106. val = t0 < t1;
  107. t0 = GET_VALUE(2); t1 = GET_VALUE(3);
  108. val |= (t0 < t1) << 1;
  109. t0 = GET_VALUE(4); t1 = GET_VALUE(5);
  110. val |= (t0 < t1) << 2;
  111. t0 = GET_VALUE(6); t1 = GET_VALUE(7);
  112. val |= (t0 < t1) << 3;
  113. t0 = GET_VALUE(8); t1 = GET_VALUE(9);
  114. val |= (t0 < t1) << 4;
  115. t0 = GET_VALUE(10); t1 = GET_VALUE(11);
  116. val |= (t0 < t1) << 5;
  117. t0 = GET_VALUE(12); t1 = GET_VALUE(13);
  118. val |= (t0 < t1) << 6;
  119. t0 = GET_VALUE(14); t1 = GET_VALUE(15);
  120. val |= (t0 < t1) << 7;
  121. desc[i] = (uchar)val;
  122. }
  123. #undef GET_VALUE
  124. }
  125. static int bit_pattern_31_[256*4] =
  126. {
  127. 8,-3, 9,5/*mean (0), correlation (0)*/,
  128. 4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
  129. -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
  130. 7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
  131. 2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
  132. 1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
  133. -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
  134. -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
  135. -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
  136. 10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
  137. -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
  138. -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
  139. 7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
  140. -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
  141. -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
  142. -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
  143. 12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
  144. -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
  145. -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
  146. 11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/,
  147. 4,7, 5,1/*mean (0.205106), correlation (0.186848)*/,
  148. 5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/,
  149. 3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/,
  150. -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/,
  151. -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/,
  152. -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/,
  153. -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/,
  154. -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/,
  155. -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/,
  156. 5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/,
  157. 5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/,
  158. 1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/,
  159. 9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/,
  160. 4,7, 4,12/*mean (0.131005), correlation (0.257622)*/,
  161. 2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/,
  162. -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/,
  163. -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/,
  164. 4,11, 9,12/*mean (0.226226), correlation (0.258255)*/,
  165. 0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/,
  166. -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/,
  167. -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/,
  168. -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/,
  169. 8,12, 10,7/*mean (0.225337), correlation (0.282851)*/,
  170. 0,9, 1,3/*mean (0.226687), correlation (0.278734)*/,
  171. 7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/,
  172. -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/,
  173. 10,7, 12,1/*mean (0.125517), correlation (0.31089)*/,
  174. -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/,
  175. 10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/,
  176. -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/,
  177. -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/,
  178. 3,3, 7,8/*mean (0.177755), correlation (0.309394)*/,
  179. 5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/,
  180. -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/,
  181. 3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/,
  182. 2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/,
  183. -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/,
  184. -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/,
  185. -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/,
  186. -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/,
  187. 6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/,
  188. -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/,
  189. -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/,
  190. -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/,
  191. 3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/,
  192. -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/,
  193. -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/,
  194. 2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/,
  195. -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/,
  196. -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/,
  197. 5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/,
  198. -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/,
  199. -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/,
  200. -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/,
  201. 10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/,
  202. 7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/,
  203. -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/,
  204. -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/,
  205. 7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/,
  206. -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/,
  207. -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/,
  208. -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/,
  209. 7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/,
  210. -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/,
  211. 1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/,
  212. 2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/,
  213. -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/,
  214. -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/,
  215. 7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/,
  216. 1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/,
  217. 9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/,
  218. -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/,
  219. -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/,
  220. 7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/,
  221. 12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/,
  222. 6,3, 7,11/*mean (0.1074), correlation (0.413224)*/,
  223. 5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/,
  224. 2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/,
  225. 3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/,
  226. 2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/,
  227. 9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/,
  228. -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/,
  229. -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/,
  230. 1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/,
  231. 6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/,
  232. 2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/,
  233. 6,3, 11,0/*mean (0.204588), correlation (0.411762)*/,
  234. 3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/,
  235. 7,8, 9,3/*mean (0.213237), correlation (0.409306)*/,
  236. -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/,
  237. -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/,
  238. -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/,
  239. -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/,
  240. 8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/,
  241. 4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/,
  242. -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/,
  243. 4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/,
  244. -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/,
  245. -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/,
  246. 7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/,
  247. -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/,
  248. -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/,
  249. 8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/,
  250. -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/,
  251. 1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/,
  252. 7,-4, 9,1/*mean (0.132692), correlation (0.454)*/,
  253. -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/,
  254. 11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/,
  255. -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/,
  256. 3,7, 7,12/*mean (0.147627), correlation (0.456643)*/,
  257. 5,5, 10,8/*mean (0.152901), correlation (0.455036)*/,
  258. 0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/,
  259. -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/,
  260. 0,7, 2,12/*mean (0.18312), correlation (0.433855)*/,
  261. -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/,
  262. 5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/,
  263. 3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/,
  264. -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/,
  265. -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/,
  266. -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/,
  267. 6,5, 8,0/*mean (0.1972), correlation (0.450481)*/,
  268. -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/,
  269. -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/,
  270. 1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/,
  271. 4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/,
  272. -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/,
  273. 2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/,
  274. -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/,
  275. 4,1, 9,3/*mean (0.23962), correlation (0.444824)*/,
  276. -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/,
  277. -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/,
  278. 7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/,
  279. 4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/,
  280. -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/,
  281. 7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/,
  282. 7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/,
  283. -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/,
  284. -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/,
  285. -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/,
  286. 2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/,
  287. 10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/,
  288. -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/,
  289. 8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/,
  290. 2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/,
  291. -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/,
  292. -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/,
  293. -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/,
  294. 5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/,
  295. -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/,
  296. -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/,
  297. -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/,
  298. -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/,
  299. -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/,
  300. 2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/,
  301. -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/,
  302. -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/,
  303. -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/,
  304. -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/,
  305. 6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/,
  306. -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/,
  307. 11,11, 12,6/*mean (0.16652), correlation (0.497632)*/,
  308. 7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/,
  309. -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/,
  310. -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/,
  311. -7,1, -6,7/*mean (0.175), correlation (0.500024)*/,
  312. -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/,
  313. -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/,
  314. -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/,
  315. -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/,
  316. -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/,
  317. 1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/,
  318. 1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/,
  319. 9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/,
  320. 5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/,
  321. -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/,
  322. -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/,
  323. -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/,
  324. -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/,
  325. 8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/,
  326. 2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/,
  327. 7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/,
  328. -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/,
  329. -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/,
  330. 4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/,
  331. 3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/,
  332. -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/,
  333. 5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/,
  334. 4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/,
  335. -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/,
  336. 0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/,
  337. -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/,
  338. 3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/,
  339. -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/,
  340. 8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/,
  341. -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/,
  342. 2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/,
  343. 10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/,
  344. 6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/,
  345. -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/,
  346. -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/,
  347. -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/,
  348. -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/,
  349. -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/,
  350. 4,2, 12,12/*mean (0.01778), correlation (0.546921)*/,
  351. 2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/,
  352. 6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/,
  353. 3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/,
  354. 11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/,
  355. -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/,
  356. 4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/,
  357. 2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/,
  358. -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/,
  359. -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/,
  360. -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/,
  361. 6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/,
  362. 0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/,
  363. -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/,
  364. -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/,
  365. -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/,
  366. 5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/,
  367. 2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/,
  368. -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/,
  369. 9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/,
  370. 11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/,
  371. 3,0, 3,5/*mean (0.101147), correlation (0.525576)*/,
  372. -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/,
  373. 3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/,
  374. -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/,
  375. 5,8, 12,11/*mean (0.114181), correlation (0.555793)*/,
  376. 8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/,
  377. 7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/,
  378. -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/,
  379. 7,3, 12,4/*mean (0.122582), correlation (0.555825)*/,
  380. 9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/,
  381. 7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/,
  382. -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/
  383. };
  384. ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
  385. int _iniThFAST, int _minThFAST):
  386. nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
  387. iniThFAST(_iniThFAST), minThFAST(_minThFAST)
  388. {
  389. mvScaleFactor.resize(nlevels);
  390. mvLevelSigma2.resize(nlevels);
  391. mvScaleFactor[0]=1.0f;
  392. mvLevelSigma2[0]=1.0f;
  393. for(int i=1; i<nlevels; i++)
  394. {
  395. mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
  396. mvLevelSigma2[i]=mvScaleFactor[i]*mvScaleFactor[i];
  397. }
  398. mvInvScaleFactor.resize(nlevels);
  399. mvInvLevelSigma2.resize(nlevels);
  400. for(int i=0; i<nlevels; i++)
  401. {
  402. mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
  403. mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
  404. }
  405. mvImagePyramid.resize(nlevels);
  406. mnFeaturesPerLevel.resize(nlevels);
  407. float factor = 1.0f / scaleFactor;
  408. float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
  409. int sumFeatures = 0;
  410. for( int level = 0; level < nlevels-1; level++ )
  411. {
  412. mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
  413. sumFeatures += mnFeaturesPerLevel[level];
  414. nDesiredFeaturesPerScale *= factor;
  415. }
  416. mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
  417. const int npoints = 512;
  418. const Point* pattern0 = (const Point*)bit_pattern_31_;
  419. std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
  420. //This is for orientation
  421. // pre-compute the end of a row in a circular patch
  422. umax.resize(HALF_PATCH_SIZE + 1);
  423. int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);
  424. int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);
  425. const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;
  426. for (v = 0; v <= vmax; ++v)
  427. umax[v] = cvRound(sqrt(hp2 - v * v));
  428. // Make sure we are symmetric
  429. for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
  430. {
  431. while (umax[v0] == umax[v0 + 1])
  432. ++v0;
  433. umax[v] = v0;
  434. ++v0;
  435. }
  436. }
  437. static void computeOrientation(const Mat& image, vector<KeyPoint>& keypoints, const vector<int>& umax)
  438. {
  439. for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
  440. keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
  441. {
  442. keypoint->angle = IC_Angle(image, keypoint->pt, umax);
  443. }
  444. }
  445. void ExtractorNode::DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4)
  446. {
  447. const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
  448. const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);
  449. //Define boundaries of childs
  450. n1.UL = UL;
  451. n1.UR = cv::Point2i(UL.x+halfX,UL.y);
  452. n1.BL = cv::Point2i(UL.x,UL.y+halfY);
  453. n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
  454. n1.vKeys.reserve(vKeys.size());
  455. n2.UL = n1.UR;
  456. n2.UR = UR;
  457. n2.BL = n1.BR;
  458. n2.BR = cv::Point2i(UR.x,UL.y+halfY);
  459. n2.vKeys.reserve(vKeys.size());
  460. n3.UL = n1.BL;
  461. n3.UR = n1.BR;
  462. n3.BL = BL;
  463. n3.BR = cv::Point2i(n1.BR.x,BL.y);
  464. n3.vKeys.reserve(vKeys.size());
  465. n4.UL = n3.UR;
  466. n4.UR = n2.BR;
  467. n4.BL = n3.BR;
  468. n4.BR = BR;
  469. n4.vKeys.reserve(vKeys.size());
  470. //Associate points to childs
  471. for(size_t i=0;i<vKeys.size();i++)
  472. {
  473. const cv::KeyPoint &kp = vKeys[i];
  474. if(kp.pt.x<n1.UR.x)
  475. {
  476. if(kp.pt.y<n1.BR.y)
  477. n1.vKeys.push_back(kp);
  478. else
  479. n3.vKeys.push_back(kp);
  480. }
  481. else if(kp.pt.y<n1.BR.y)
  482. n2.vKeys.push_back(kp);
  483. else
  484. n4.vKeys.push_back(kp);
  485. }
  486. if(n1.vKeys.size()==1)
  487. n1.bNoMore = true;
  488. if(n2.vKeys.size()==1)
  489. n2.bNoMore = true;
  490. if(n3.vKeys.size()==1)
  491. n3.bNoMore = true;
  492. if(n4.vKeys.size()==1)
  493. n4.bNoMore = true;
  494. }
  495. vector<cv::KeyPoint> ORBextractor::DistributeOctTree(const vector<cv::KeyPoint>& vToDistributeKeys, const int &minX,
  496. const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
  497. {
  498. // Compute how many initial nodes
  499. const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));
  500. const float hX = static_cast<float>(maxX-minX)/nIni;
  501. list<ExtractorNode> lNodes;
  502. vector<ExtractorNode*> vpIniNodes;
  503. vpIniNodes.resize(nIni);
  504. for(int i=0; i<nIni; i++)
  505. {
  506. ExtractorNode ni;
  507. ni.UL = cv::Point2i(hX*static_cast<float>(i),0);
  508. ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
  509. ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
  510. ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
  511. ni.vKeys.reserve(vToDistributeKeys.size());
  512. lNodes.push_back(ni);
  513. vpIniNodes[i] = &lNodes.back();
  514. }
  515. //Associate points to childs
  516. for(size_t i=0;i<vToDistributeKeys.size();i++)
  517. {
  518. const cv::KeyPoint &kp = vToDistributeKeys[i];
  519. vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
  520. }
  521. list<ExtractorNode>::iterator lit = lNodes.begin();
  522. while(lit!=lNodes.end())
  523. {
  524. if(lit->vKeys.size()==1)
  525. {
  526. lit->bNoMore=true;
  527. lit++;
  528. }
  529. else if(lit->vKeys.empty())
  530. lit = lNodes.erase(lit);
  531. else
  532. lit++;
  533. }
  534. bool bFinish = false;
  535. int iteration = 0;
  536. vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
  537. vSizeAndPointerToNode.reserve(lNodes.size()*4);
  538. while(!bFinish)
  539. {
  540. iteration++;
  541. int prevSize = lNodes.size();
  542. lit = lNodes.begin();
  543. int nToExpand = 0;
  544. vSizeAndPointerToNode.clear();
  545. while(lit!=lNodes.end())
  546. {
  547. if(lit->bNoMore)
  548. {
  549. // If node only contains one point do not subdivide and continue
  550. lit++;
  551. continue;
  552. }
  553. else
  554. {
  555. // If more than one point, subdivide
  556. ExtractorNode n1,n2,n3,n4;
  557. lit->DivideNode(n1,n2,n3,n4);
  558. // Add childs if they contain points
  559. if(n1.vKeys.size()>0)
  560. {
  561. lNodes.push_front(n1);
  562. if(n1.vKeys.size()>1)
  563. {
  564. nToExpand++;
  565. vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
  566. lNodes.front().lit = lNodes.begin();
  567. }
  568. }
  569. if(n2.vKeys.size()>0)
  570. {
  571. lNodes.push_front(n2);
  572. if(n2.vKeys.size()>1)
  573. {
  574. nToExpand++;
  575. vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
  576. lNodes.front().lit = lNodes.begin();
  577. }
  578. }
  579. if(n3.vKeys.size()>0)
  580. {
  581. lNodes.push_front(n3);
  582. if(n3.vKeys.size()>1)
  583. {
  584. nToExpand++;
  585. vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
  586. lNodes.front().lit = lNodes.begin();
  587. }
  588. }
  589. if(n4.vKeys.size()>0)
  590. {
  591. lNodes.push_front(n4);
  592. if(n4.vKeys.size()>1)
  593. {
  594. nToExpand++;
  595. vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
  596. lNodes.front().lit = lNodes.begin();
  597. }
  598. }
  599. lit=lNodes.erase(lit);
  600. continue;
  601. }
  602. }
  603. // Finish if there are more nodes than required features
  604. // or all nodes contain just one point
  605. if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
  606. {
  607. bFinish = true;
  608. }
  609. else if(((int)lNodes.size()+nToExpand*3)>N)
  610. {
  611. while(!bFinish)
  612. {
  613. prevSize = lNodes.size();
  614. vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
  615. vSizeAndPointerToNode.clear();
  616. sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
  617. for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
  618. {
  619. ExtractorNode n1,n2,n3,n4;
  620. vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);
  621. // Add childs if they contain points
  622. if(n1.vKeys.size()>0)
  623. {
  624. lNodes.push_front(n1);
  625. if(n1.vKeys.size()>1)
  626. {
  627. vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
  628. lNodes.front().lit = lNodes.begin();
  629. }
  630. }
  631. if(n2.vKeys.size()>0)
  632. {
  633. lNodes.push_front(n2);
  634. if(n2.vKeys.size()>1)
  635. {
  636. vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
  637. lNodes.front().lit = lNodes.begin();
  638. }
  639. }
  640. if(n3.vKeys.size()>0)
  641. {
  642. lNodes.push_front(n3);
  643. if(n3.vKeys.size()>1)
  644. {
  645. vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
  646. lNodes.front().lit = lNodes.begin();
  647. }
  648. }
  649. if(n4.vKeys.size()>0)
  650. {
  651. lNodes.push_front(n4);
  652. if(n4.vKeys.size()>1)
  653. {
  654. vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
  655. lNodes.front().lit = lNodes.begin();
  656. }
  657. }
  658. lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);
  659. if((int)lNodes.size()>=N)
  660. break;
  661. }
  662. if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
  663. bFinish = true;
  664. }
  665. }
  666. }
  667. // Retain the best point in each node
  668. vector<cv::KeyPoint> vResultKeys;
  669. vResultKeys.reserve(nfeatures);
  670. for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
  671. {
  672. vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
  673. cv::KeyPoint* pKP = &vNodeKeys[0];
  674. float maxResponse = pKP->response;
  675. for(size_t k=1;k<vNodeKeys.size();k++)
  676. {
  677. if(vNodeKeys[k].response>maxResponse)
  678. {
  679. pKP = &vNodeKeys[k];
  680. maxResponse = vNodeKeys[k].response;
  681. }
  682. }
  683. vResultKeys.push_back(*pKP);
  684. }
  685. return vResultKeys;
  686. }
  687. void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
  688. {
  689. allKeypoints.resize(nlevels);
  690. const float W = 35;
  691. for (int level = 0; level < nlevels; ++level)
  692. {
  693. const int minBorderX = EDGE_THRESHOLD-3;
  694. const int minBorderY = minBorderX;
  695. const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
  696. const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
  697. vector<cv::KeyPoint> vToDistributeKeys;
  698. vToDistributeKeys.reserve(nfeatures*10);
  699. const float width = (maxBorderX-minBorderX);
  700. const float height = (maxBorderY-minBorderY);
  701. const int nCols = width/W;
  702. const int nRows = height/W;
  703. const int wCell = ceil(width/nCols);
  704. const int hCell = ceil(height/nRows);
  705. for(int i=0; i<nRows; i++)
  706. {
  707. const float iniY =minBorderY+i*hCell;
  708. float maxY = iniY+hCell+6;
  709. if(iniY>=maxBorderY-3)
  710. continue;
  711. if(maxY>maxBorderY)
  712. maxY = maxBorderY;
  713. for(int j=0; j<nCols; j++)
  714. {
  715. const float iniX =minBorderX+j*wCell;
  716. float maxX = iniX+wCell+6;
  717. if(iniX>=maxBorderX-6)
  718. continue;
  719. if(maxX>maxBorderX)
  720. maxX = maxBorderX;
  721. vector<cv::KeyPoint> vKeysCell;
  722. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  723. vKeysCell,iniThFAST,true);
  724. /*if(bRight && j <= 13){
  725. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  726. vKeysCell,10,true);
  727. }
  728. else if(!bRight && j >= 16){
  729. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  730. vKeysCell,10,true);
  731. }
  732. else{
  733. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  734. vKeysCell,iniThFAST,true);
  735. }*/
  736. if(vKeysCell.empty())
  737. {
  738. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  739. vKeysCell,minThFAST,true);
  740. /*if(bRight && j <= 13){
  741. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  742. vKeysCell,5,true);
  743. }
  744. else if(!bRight && j >= 16){
  745. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  746. vKeysCell,5,true);
  747. }
  748. else{
  749. FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
  750. vKeysCell,minThFAST,true);
  751. }*/
  752. }
  753. if(!vKeysCell.empty())
  754. {
  755. for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
  756. {
  757. (*vit).pt.x+=j*wCell;
  758. (*vit).pt.y+=i*hCell;
  759. vToDistributeKeys.push_back(*vit);
  760. }
  761. }
  762. }
  763. }
  764. vector<KeyPoint> & keypoints = allKeypoints[level];
  765. keypoints.reserve(nfeatures);
  766. keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
  767. minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
  768. const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
  769. // Add border to coordinates and scale information
  770. const int nkps = keypoints.size();
  771. for(int i=0; i<nkps ; i++)
  772. {
  773. keypoints[i].pt.x+=minBorderX;
  774. keypoints[i].pt.y+=minBorderY;
  775. keypoints[i].octave=level;
  776. keypoints[i].size = scaledPatchSize;
  777. }
  778. }
  779. // compute orientations
  780. for (int level = 0; level < nlevels; ++level)
  781. computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
  782. }
  783. void ORBextractor::ComputeKeyPointsOld(std::vector<std::vector<KeyPoint> > &allKeypoints)
  784. {
  785. allKeypoints.resize(nlevels);
  786. float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows;
  787. for (int level = 0; level < nlevels; ++level)
  788. {
  789. const int nDesiredFeatures = mnFeaturesPerLevel[level];
  790. const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio));
  791. const int levelRows = imageRatio*levelCols;
  792. const int minBorderX = EDGE_THRESHOLD;
  793. const int minBorderY = minBorderX;
  794. const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD;
  795. const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD;
  796. const int W = maxBorderX - minBorderX;
  797. const int H = maxBorderY - minBorderY;
  798. const int cellW = ceil((float)W/levelCols);
  799. const int cellH = ceil((float)H/levelRows);
  800. const int nCells = levelRows*levelCols;
  801. const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells);
  802. vector<vector<vector<KeyPoint> > > cellKeyPoints(levelRows, vector<vector<KeyPoint> >(levelCols));
  803. vector<vector<int> > nToRetain(levelRows,vector<int>(levelCols,0));
  804. vector<vector<int> > nTotal(levelRows,vector<int>(levelCols,0));
  805. vector<vector<bool> > bNoMore(levelRows,vector<bool>(levelCols,false));
  806. vector<int> iniXCol(levelCols);
  807. vector<int> iniYRow(levelRows);
  808. int nNoMore = 0;
  809. int nToDistribute = 0;
  810. float hY = cellH + 6;
  811. for(int i=0; i<levelRows; i++)
  812. {
  813. const float iniY = minBorderY + i*cellH - 3;
  814. iniYRow[i] = iniY;
  815. if(i == levelRows-1)
  816. {
  817. hY = maxBorderY+3-iniY;
  818. if(hY<=0)
  819. continue;
  820. }
  821. float hX = cellW + 6;
  822. for(int j=0; j<levelCols; j++)
  823. {
  824. float iniX;
  825. if(i==0)
  826. {
  827. iniX = minBorderX + j*cellW - 3;
  828. iniXCol[j] = iniX;
  829. }
  830. else
  831. {
  832. iniX = iniXCol[j];
  833. }
  834. if(j == levelCols-1)
  835. {
  836. hX = maxBorderX+3-iniX;
  837. if(hX<=0)
  838. continue;
  839. }
  840. Mat cellImage = mvImagePyramid[level].rowRange(iniY,iniY+hY).colRange(iniX,iniX+hX);
  841. cellKeyPoints[i][j].reserve(nfeaturesCell*5);
  842. FAST(cellImage,cellKeyPoints[i][j],iniThFAST,true);
  843. if(cellKeyPoints[i][j].size()<=3)
  844. {
  845. cellKeyPoints[i][j].clear();
  846. FAST(cellImage,cellKeyPoints[i][j],minThFAST,true);
  847. }
  848. const int nKeys = cellKeyPoints[i][j].size();
  849. nTotal[i][j] = nKeys;
  850. if(nKeys>nfeaturesCell)
  851. {
  852. nToRetain[i][j] = nfeaturesCell;
  853. bNoMore[i][j] = false;
  854. }
  855. else
  856. {
  857. nToRetain[i][j] = nKeys;
  858. nToDistribute += nfeaturesCell-nKeys;
  859. bNoMore[i][j] = true;
  860. nNoMore++;
  861. }
  862. }
  863. }
  864. // Retain by score
  865. while(nToDistribute>0 && nNoMore<nCells)
  866. {
  867. int nNewFeaturesCell = nfeaturesCell + ceil((float)nToDistribute/(nCells-nNoMore));
  868. nToDistribute = 0;
  869. for(int i=0; i<levelRows; i++)
  870. {
  871. for(int j=0; j<levelCols; j++)
  872. {
  873. if(!bNoMore[i][j])
  874. {
  875. if(nTotal[i][j]>nNewFeaturesCell)
  876. {
  877. nToRetain[i][j] = nNewFeaturesCell;
  878. bNoMore[i][j] = false;
  879. }
  880. else
  881. {
  882. nToRetain[i][j] = nTotal[i][j];
  883. nToDistribute += nNewFeaturesCell-nTotal[i][j];
  884. bNoMore[i][j] = true;
  885. nNoMore++;
  886. }
  887. }
  888. }
  889. }
  890. }
  891. vector<KeyPoint> & keypoints = allKeypoints[level];
  892. keypoints.reserve(nDesiredFeatures*2);
  893. const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
  894. // Retain by score and transform coordinates
  895. for(int i=0; i<levelRows; i++)
  896. {
  897. for(int j=0; j<levelCols; j++)
  898. {
  899. vector<KeyPoint> &keysCell = cellKeyPoints[i][j];
  900. KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]);
  901. if((int)keysCell.size()>nToRetain[i][j])
  902. keysCell.resize(nToRetain[i][j]);
  903. for(size_t k=0, kend=keysCell.size(); k<kend; k++)
  904. {
  905. keysCell[k].pt.x+=iniXCol[j];
  906. keysCell[k].pt.y+=iniYRow[i];
  907. keysCell[k].octave=level;
  908. keysCell[k].size = scaledPatchSize;
  909. keypoints.push_back(keysCell[k]);
  910. }
  911. }
  912. }
  913. if((int)keypoints.size()>nDesiredFeatures)
  914. {
  915. KeyPointsFilter::retainBest(keypoints,nDesiredFeatures);
  916. keypoints.resize(nDesiredFeatures);
  917. }
  918. }
  919. // and compute orientations
  920. for (int level = 0; level < nlevels; ++level)
  921. computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
  922. }
  923. static void computeDescriptors(const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors,
  924. const vector<Point>& pattern)
  925. {
  926. descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);
  927. for (size_t i = 0; i < keypoints.size(); i++)
  928. computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i));
  929. }
  930. int ORBextractor::operator()( InputArray _image, InputArray _mask, vector<KeyPoint>& _keypoints,
  931. OutputArray _descriptors, std::vector<int> &vLappingArea)
  932. {
  933. //cout << "[ORBextractor]: Max Features: " << nfeatures << endl;
  934. if(_image.empty())
  935. return -1;
  936. Mat image = _image.getMat();
  937. assert(image.type() == CV_8UC1 );
  938. // Pre-compute the scale pyramid
  939. ComputePyramid(image);
  940. vector < vector<KeyPoint> > allKeypoints;
  941. ComputeKeyPointsOctTree(allKeypoints);
  942. //ComputeKeyPointsOld(allKeypoints);
  943. Mat descriptors;
  944. int nkeypoints = 0;
  945. for (int level = 0; level < nlevels; ++level)
  946. nkeypoints += (int)allKeypoints[level].size();
  947. if( nkeypoints == 0 )
  948. _descriptors.release();
  949. else
  950. {
  951. _descriptors.create(nkeypoints, 32, CV_8U);
  952. descriptors = _descriptors.getMat();
  953. }
  954. //_keypoints.clear();
  955. //_keypoints.reserve(nkeypoints);
  956. _keypoints = vector<cv::KeyPoint>(nkeypoints);
  957. int offset = 0;
  958. //Modified for speeding up stereo fisheye matching
  959. int monoIndex = 0, stereoIndex = nkeypoints-1;
  960. for (int level = 0; level < nlevels; ++level)
  961. {
  962. vector<KeyPoint>& keypoints = allKeypoints[level];
  963. int nkeypointsLevel = (int)keypoints.size();
  964. if(nkeypointsLevel==0)
  965. continue;
  966. // preprocess the resized image
  967. Mat workingMat = mvImagePyramid[level].clone();
  968. GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
  969. // Compute the descriptors
  970. //Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
  971. Mat desc = cv::Mat(nkeypointsLevel, 32, CV_8U);
  972. computeDescriptors(workingMat, keypoints, desc, pattern);
  973. offset += nkeypointsLevel;
  974. float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor);
  975. int i = 0;
  976. for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
  977. keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint){
  978. // Scale keypoint coordinates
  979. if (level != 0){
  980. keypoint->pt *= scale;
  981. }
  982. if(keypoint->pt.x >= vLappingArea[0] && keypoint->pt.x <= vLappingArea[1]){
  983. _keypoints.at(stereoIndex) = (*keypoint);
  984. desc.row(i).copyTo(descriptors.row(stereoIndex));
  985. stereoIndex--;
  986. }
  987. else{
  988. _keypoints.at(monoIndex) = (*keypoint);
  989. desc.row(i).copyTo(descriptors.row(monoIndex));
  990. monoIndex++;
  991. }
  992. i++;
  993. }
  994. }
  995. //cout << "[ORBextractor]: extracted " << _keypoints.size() << " KeyPoints" << endl;
  996. return monoIndex;
  997. }
  998. void ORBextractor::ComputePyramid(cv::Mat image)
  999. {
  1000. for (int level = 0; level < nlevels; ++level)
  1001. {
  1002. float scale = mvInvScaleFactor[level];
  1003. Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
  1004. Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
  1005. Mat temp(wholeSize, image.type()), masktemp;
  1006. mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
  1007. // Compute the resized image
  1008. if( level != 0 )
  1009. {
  1010. resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
  1011. copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
  1012. BORDER_REFLECT_101+BORDER_ISOLATED);
  1013. }
  1014. else
  1015. {
  1016. copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
  1017. BORDER_REFLECT_101);
  1018. }
  1019. }
  1020. }
  1021. } //namespace ORB_SLAM