LocalMapping.cc 50 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 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. #include "LocalMapping.h"
  19. #include "LoopClosing.h"
  20. #include "ORBmatcher.h"
  21. #include "Optimizer.h"
  22. #include "Converter.h"
  23. #include "GeometricTools.h"
  24. #include<mutex>
  25. #include<chrono>
  26. namespace ORB_SLAM3
  27. {
  28. LocalMapping::LocalMapping(System* pSys, Atlas *pAtlas, const float bMonocular, bool bInertial, const string &_strSeqName):
  29. mpSystem(pSys), mbMonocular(bMonocular), mbInertial(bInertial), mbResetRequested(false), mbResetRequestedActiveMap(false), mbFinishRequested(false), mbFinished(true), mpAtlas(pAtlas), bInitializing(false),
  30. mbAbortBA(false), mbStopped(false), mbStopRequested(false), mbNotStop(false), mbAcceptKeyFrames(true),
  31. mIdxInit(0), mScale(1.0), mInitSect(0), mbNotBA1(true), mbNotBA2(true), mIdxIteration(0), infoInertial(Eigen::MatrixXd::Zero(9,9))
  32. {
  33. mnMatchesInliers = 0;
  34. mbBadImu = false;
  35. mTinit = 0.f;
  36. mNumLM = 0;
  37. mNumKFCulling=0;
  38. #ifdef REGISTER_TIMES
  39. nLBA_exec = 0;
  40. nLBA_abort = 0;
  41. #endif
  42. }
  43. void LocalMapping::SetLoopCloser(LoopClosing* pLoopCloser)
  44. {
  45. mpLoopCloser = pLoopCloser;
  46. }
  47. void LocalMapping::SetTracker(Tracking *pTracker)
  48. {
  49. mpTracker=pTracker;
  50. }
  51. void LocalMapping::Run()
  52. {
  53. mbFinished = false;
  54. while(1)
  55. {
  56. // Tracking will see that Local Mapping is busy
  57. SetAcceptKeyFrames(false);
  58. // Check if there are keyframes in the queue
  59. if(CheckNewKeyFrames() && !mbBadImu)
  60. {
  61. #ifdef REGISTER_TIMES
  62. double timeLBA_ms = 0;
  63. double timeKFCulling_ms = 0;
  64. std::chrono::steady_clock::time_point time_StartProcessKF = std::chrono::steady_clock::now();
  65. #endif
  66. // BoW conversion and insertion in Map
  67. ProcessNewKeyFrame();
  68. #ifdef REGISTER_TIMES
  69. std::chrono::steady_clock::time_point time_EndProcessKF = std::chrono::steady_clock::now();
  70. double timeProcessKF = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndProcessKF - time_StartProcessKF).count();
  71. vdKFInsert_ms.push_back(timeProcessKF);
  72. #endif
  73. // Check recent MapPoints
  74. MapPointCulling();
  75. #ifdef REGISTER_TIMES
  76. std::chrono::steady_clock::time_point time_EndMPCulling = std::chrono::steady_clock::now();
  77. double timeMPCulling = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMPCulling - time_EndProcessKF).count();
  78. vdMPCulling_ms.push_back(timeMPCulling);
  79. #endif
  80. // Triangulate new MapPoints
  81. CreateNewMapPoints();
  82. mbAbortBA = false;
  83. if(!CheckNewKeyFrames())
  84. {
  85. // Find more matches in neighbor keyframes and fuse point duplications
  86. SearchInNeighbors();
  87. }
  88. #ifdef REGISTER_TIMES
  89. std::chrono::steady_clock::time_point time_EndMPCreation = std::chrono::steady_clock::now();
  90. double timeMPCreation = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMPCreation - time_EndMPCulling).count();
  91. vdMPCreation_ms.push_back(timeMPCreation);
  92. #endif
  93. bool b_doneLBA = false;
  94. int num_FixedKF_BA = 0;
  95. int num_OptKF_BA = 0;
  96. int num_MPs_BA = 0;
  97. int num_edges_BA = 0;
  98. if(!CheckNewKeyFrames() && !stopRequested())
  99. {
  100. if(mpAtlas->KeyFramesInMap()>2)
  101. {
  102. if(mbInertial && mpCurrentKeyFrame->GetMap()->isImuInitialized())
  103. {
  104. float dist = (mpCurrentKeyFrame->mPrevKF->GetCameraCenter() - mpCurrentKeyFrame->GetCameraCenter()).norm() +
  105. (mpCurrentKeyFrame->mPrevKF->mPrevKF->GetCameraCenter() - mpCurrentKeyFrame->mPrevKF->GetCameraCenter()).norm();
  106. if(dist>0.05)
  107. mTinit += mpCurrentKeyFrame->mTimeStamp - mpCurrentKeyFrame->mPrevKF->mTimeStamp;
  108. if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2())
  109. {
  110. if((mTinit<10.f) && (dist<0.02))
  111. {
  112. cout << "Not enough motion for initializing. Reseting..." << endl;
  113. unique_lock<mutex> lock(mMutexReset);
  114. mbResetRequestedActiveMap = true;
  115. mpMapToReset = mpCurrentKeyFrame->GetMap();
  116. mbBadImu = true;
  117. }
  118. }
  119. bool bLarge = ((mpTracker->GetMatchesInliers()>75)&&mbMonocular)||((mpTracker->GetMatchesInliers()>100)&&!mbMonocular);
  120. Optimizer::LocalInertialBA(mpCurrentKeyFrame, &mbAbortBA, mpCurrentKeyFrame->GetMap(),num_FixedKF_BA,num_OptKF_BA,num_MPs_BA,num_edges_BA, bLarge, !mpCurrentKeyFrame->GetMap()->GetIniertialBA2());
  121. b_doneLBA = true;
  122. }
  123. else
  124. {
  125. Optimizer::LocalBundleAdjustment(mpCurrentKeyFrame,&mbAbortBA, mpCurrentKeyFrame->GetMap(),num_FixedKF_BA,num_OptKF_BA,num_MPs_BA,num_edges_BA);
  126. b_doneLBA = true;
  127. }
  128. }
  129. #ifdef REGISTER_TIMES
  130. std::chrono::steady_clock::time_point time_EndLBA = std::chrono::steady_clock::now();
  131. if(b_doneLBA)
  132. {
  133. timeLBA_ms = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndLBA - time_EndMPCreation).count();
  134. vdLBA_ms.push_back(timeLBA_ms);
  135. nLBA_exec += 1;
  136. if(mbAbortBA)
  137. {
  138. nLBA_abort += 1;
  139. }
  140. vnLBA_edges.push_back(num_edges_BA);
  141. vnLBA_KFopt.push_back(num_OptKF_BA);
  142. vnLBA_KFfixed.push_back(num_FixedKF_BA);
  143. vnLBA_MPs.push_back(num_MPs_BA);
  144. }
  145. #endif
  146. // Initialize IMU here
  147. if(!mpCurrentKeyFrame->GetMap()->isImuInitialized() && mbInertial)
  148. {
  149. if (mbMonocular)
  150. InitializeIMU(1e2, 1e10, true);
  151. else
  152. InitializeIMU(1e2, 1e5, true);
  153. }
  154. // Check redundant local Keyframes
  155. KeyFrameCulling();
  156. #ifdef REGISTER_TIMES
  157. std::chrono::steady_clock::time_point time_EndKFCulling = std::chrono::steady_clock::now();
  158. timeKFCulling_ms = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndKFCulling - time_EndLBA).count();
  159. vdKFCulling_ms.push_back(timeKFCulling_ms);
  160. #endif
  161. if ((mTinit<50.0f) && mbInertial)
  162. {
  163. if(mpCurrentKeyFrame->GetMap()->isImuInitialized() && mpTracker->mState==Tracking::OK) // Enter here everytime local-mapping is called
  164. {
  165. if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA1()){
  166. if (mTinit>5.0f)
  167. {
  168. cout << "start VIBA 1" << endl;
  169. mpCurrentKeyFrame->GetMap()->SetIniertialBA1();
  170. if (mbMonocular)
  171. InitializeIMU(1.f, 1e5, true);
  172. else
  173. InitializeIMU(1.f, 1e5, true);
  174. cout << "end VIBA 1" << endl;
  175. }
  176. }
  177. else if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2()){
  178. if (mTinit>15.0f){
  179. cout << "start VIBA 2" << endl;
  180. mpCurrentKeyFrame->GetMap()->SetIniertialBA2();
  181. if (mbMonocular)
  182. InitializeIMU(0.f, 0.f, true);
  183. else
  184. InitializeIMU(0.f, 0.f, true);
  185. cout << "end VIBA 2" << endl;
  186. }
  187. }
  188. // scale refinement
  189. if (((mpAtlas->KeyFramesInMap())<=200) &&
  190. ((mTinit>25.0f && mTinit<25.5f)||
  191. (mTinit>35.0f && mTinit<35.5f)||
  192. (mTinit>45.0f && mTinit<45.5f)||
  193. (mTinit>55.0f && mTinit<55.5f)||
  194. (mTinit>65.0f && mTinit<65.5f)||
  195. (mTinit>75.0f && mTinit<75.5f))){
  196. if (mbMonocular)
  197. ScaleRefinement();
  198. }
  199. }
  200. }
  201. }
  202. #ifdef REGISTER_TIMES
  203. vdLBASync_ms.push_back(timeKFCulling_ms);
  204. vdKFCullingSync_ms.push_back(timeKFCulling_ms);
  205. #endif
  206. mpLoopCloser->InsertKeyFrame(mpCurrentKeyFrame);
  207. #ifdef REGISTER_TIMES
  208. std::chrono::steady_clock::time_point time_EndLocalMap = std::chrono::steady_clock::now();
  209. double timeLocalMap = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndLocalMap - time_StartProcessKF).count();
  210. vdLMTotal_ms.push_back(timeLocalMap);
  211. #endif
  212. }
  213. else if(Stop() && !mbBadImu)
  214. {
  215. // Safe area to stop
  216. while(isStopped() && !CheckFinish())
  217. {
  218. usleep(3000);
  219. }
  220. if(CheckFinish())
  221. break;
  222. }
  223. ResetIfRequested();
  224. // Tracking will see that Local Mapping is busy
  225. SetAcceptKeyFrames(true);
  226. if(CheckFinish())
  227. break;
  228. usleep(3000);
  229. }
  230. SetFinish();
  231. }
  232. void LocalMapping::InsertKeyFrame(KeyFrame *pKF)
  233. {
  234. unique_lock<mutex> lock(mMutexNewKFs);
  235. mlNewKeyFrames.push_back(pKF);
  236. mbAbortBA=true;
  237. }
  238. bool LocalMapping::CheckNewKeyFrames()
  239. {
  240. unique_lock<mutex> lock(mMutexNewKFs);
  241. return(!mlNewKeyFrames.empty());
  242. }
  243. void LocalMapping::ProcessNewKeyFrame()
  244. {
  245. {
  246. unique_lock<mutex> lock(mMutexNewKFs);
  247. mpCurrentKeyFrame = mlNewKeyFrames.front();
  248. mlNewKeyFrames.pop_front();
  249. }
  250. // Compute Bags of Words structures
  251. mpCurrentKeyFrame->ComputeBoW();
  252. // Associate MapPoints to the new keyframe and update normal and descriptor
  253. const vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
  254. for(size_t i=0; i<vpMapPointMatches.size(); i++)
  255. {
  256. MapPoint* pMP = vpMapPointMatches[i];
  257. if(pMP)
  258. {
  259. if(!pMP->isBad())
  260. {
  261. if(!pMP->IsInKeyFrame(mpCurrentKeyFrame))
  262. {
  263. pMP->AddObservation(mpCurrentKeyFrame, i);
  264. pMP->UpdateNormalAndDepth();
  265. pMP->ComputeDistinctiveDescriptors();
  266. }
  267. else // this can only happen for new stereo points inserted by the Tracking
  268. {
  269. mlpRecentAddedMapPoints.push_back(pMP);
  270. }
  271. }
  272. }
  273. }
  274. // Update links in the Covisibility Graph
  275. mpCurrentKeyFrame->UpdateConnections();
  276. // Insert Keyframe in Map
  277. mpAtlas->AddKeyFrame(mpCurrentKeyFrame);
  278. }
  279. void LocalMapping::EmptyQueue()
  280. {
  281. while(CheckNewKeyFrames())
  282. ProcessNewKeyFrame();
  283. }
  284. void LocalMapping::MapPointCulling()
  285. {
  286. // Check Recent Added MapPoints
  287. list<MapPoint*>::iterator lit = mlpRecentAddedMapPoints.begin();
  288. const unsigned long int nCurrentKFid = mpCurrentKeyFrame->mnId;
  289. int nThObs;
  290. if(mbMonocular)
  291. nThObs = 2;
  292. else
  293. nThObs = 3;
  294. const int cnThObs = nThObs;
  295. int borrar = mlpRecentAddedMapPoints.size();
  296. while(lit!=mlpRecentAddedMapPoints.end())
  297. {
  298. MapPoint* pMP = *lit;
  299. if(pMP->isBad())
  300. lit = mlpRecentAddedMapPoints.erase(lit);
  301. else if(pMP->GetFoundRatio()<0.25f)
  302. {
  303. pMP->SetBadFlag();
  304. lit = mlpRecentAddedMapPoints.erase(lit);
  305. }
  306. else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=2 && pMP->Observations()<=cnThObs)
  307. {
  308. pMP->SetBadFlag();
  309. lit = mlpRecentAddedMapPoints.erase(lit);
  310. }
  311. else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=3)
  312. lit = mlpRecentAddedMapPoints.erase(lit);
  313. else
  314. {
  315. lit++;
  316. borrar--;
  317. }
  318. }
  319. }
  320. void LocalMapping::CreateNewMapPoints()
  321. {
  322. // Retrieve neighbor keyframes in covisibility graph
  323. int nn = 10;
  324. // For stereo inertial case
  325. if(mbMonocular)
  326. nn=30;
  327. vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);
  328. if (mbInertial)
  329. {
  330. KeyFrame* pKF = mpCurrentKeyFrame;
  331. int count=0;
  332. while((vpNeighKFs.size()<=nn)&&(pKF->mPrevKF)&&(count++<nn))
  333. {
  334. vector<KeyFrame*>::iterator it = std::find(vpNeighKFs.begin(), vpNeighKFs.end(), pKF->mPrevKF);
  335. if(it==vpNeighKFs.end())
  336. vpNeighKFs.push_back(pKF->mPrevKF);
  337. pKF = pKF->mPrevKF;
  338. }
  339. }
  340. float th = 0.6f;
  341. ORBmatcher matcher(th,false);
  342. Sophus::SE3<float> sophTcw1 = mpCurrentKeyFrame->GetPose();
  343. Eigen::Matrix<float,3,4> eigTcw1 = sophTcw1.matrix3x4();
  344. Eigen::Matrix<float,3,3> Rcw1 = eigTcw1.block<3,3>(0,0);
  345. Eigen::Matrix<float,3,3> Rwc1 = Rcw1.transpose();
  346. Eigen::Vector3f tcw1 = sophTcw1.translation();
  347. Eigen::Vector3f Ow1 = mpCurrentKeyFrame->GetCameraCenter();
  348. const float &fx1 = mpCurrentKeyFrame->fx;
  349. const float &fy1 = mpCurrentKeyFrame->fy;
  350. const float &cx1 = mpCurrentKeyFrame->cx;
  351. const float &cy1 = mpCurrentKeyFrame->cy;
  352. const float &invfx1 = mpCurrentKeyFrame->invfx;
  353. const float &invfy1 = mpCurrentKeyFrame->invfy;
  354. const float ratioFactor = 1.5f*mpCurrentKeyFrame->mfScaleFactor;
  355. int countStereo = 0;
  356. int countStereoGoodProj = 0;
  357. int countStereoAttempt = 0;
  358. int totalStereoPts = 0;
  359. // Search matches with epipolar restriction and triangulate
  360. for(size_t i=0; i<vpNeighKFs.size(); i++)
  361. {
  362. if(i>0 && CheckNewKeyFrames())
  363. return;
  364. KeyFrame* pKF2 = vpNeighKFs[i];
  365. GeometricCamera* pCamera1 = mpCurrentKeyFrame->mpCamera, *pCamera2 = pKF2->mpCamera;
  366. // Check first that baseline is not too short
  367. Eigen::Vector3f Ow2 = pKF2->GetCameraCenter();
  368. Eigen::Vector3f vBaseline = Ow2-Ow1;
  369. const float baseline = vBaseline.norm();
  370. if(!mbMonocular)
  371. {
  372. if(baseline<pKF2->mb)
  373. continue;
  374. }
  375. else
  376. {
  377. const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2);
  378. const float ratioBaselineDepth = baseline/medianDepthKF2;
  379. if(ratioBaselineDepth<0.01)
  380. continue;
  381. }
  382. // Search matches that fullfil epipolar constraint
  383. vector<pair<size_t,size_t> > vMatchedIndices;
  384. bool bCoarse = mbInertial && mpTracker->mState==Tracking::RECENTLY_LOST && mpCurrentKeyFrame->GetMap()->GetIniertialBA2();
  385. matcher.SearchForTriangulation(mpCurrentKeyFrame,pKF2,vMatchedIndices,false,bCoarse);
  386. Sophus::SE3<float> sophTcw2 = pKF2->GetPose();
  387. Eigen::Matrix<float,3,4> eigTcw2 = sophTcw2.matrix3x4();
  388. Eigen::Matrix<float,3,3> Rcw2 = eigTcw2.block<3,3>(0,0);
  389. Eigen::Matrix<float,3,3> Rwc2 = Rcw2.transpose();
  390. Eigen::Vector3f tcw2 = sophTcw2.translation();
  391. const float &fx2 = pKF2->fx;
  392. const float &fy2 = pKF2->fy;
  393. const float &cx2 = pKF2->cx;
  394. const float &cy2 = pKF2->cy;
  395. const float &invfx2 = pKF2->invfx;
  396. const float &invfy2 = pKF2->invfy;
  397. // Triangulate each match
  398. const int nmatches = vMatchedIndices.size();
  399. for(int ikp=0; ikp<nmatches; ikp++)
  400. {
  401. const int &idx1 = vMatchedIndices[ikp].first;
  402. const int &idx2 = vMatchedIndices[ikp].second;
  403. const cv::KeyPoint &kp1 = (mpCurrentKeyFrame -> NLeft == -1) ? mpCurrentKeyFrame->mvKeysUn[idx1]
  404. : (idx1 < mpCurrentKeyFrame -> NLeft) ? mpCurrentKeyFrame -> mvKeys[idx1]
  405. : mpCurrentKeyFrame -> mvKeysRight[idx1 - mpCurrentKeyFrame -> NLeft];
  406. const float kp1_ur=mpCurrentKeyFrame->mvuRight[idx1];
  407. bool bStereo1 = (!mpCurrentKeyFrame->mpCamera2 && kp1_ur>=0);
  408. const bool bRight1 = (mpCurrentKeyFrame -> NLeft == -1 || idx1 < mpCurrentKeyFrame -> NLeft) ? false
  409. : true;
  410. const cv::KeyPoint &kp2 = (pKF2 -> NLeft == -1) ? pKF2->mvKeysUn[idx2]
  411. : (idx2 < pKF2 -> NLeft) ? pKF2 -> mvKeys[idx2]
  412. : pKF2 -> mvKeysRight[idx2 - pKF2 -> NLeft];
  413. const float kp2_ur = pKF2->mvuRight[idx2];
  414. bool bStereo2 = (!pKF2->mpCamera2 && kp2_ur>=0);
  415. const bool bRight2 = (pKF2 -> NLeft == -1 || idx2 < pKF2 -> NLeft) ? false
  416. : true;
  417. if(mpCurrentKeyFrame->mpCamera2 && pKF2->mpCamera2){
  418. if(bRight1 && bRight2){
  419. sophTcw1 = mpCurrentKeyFrame->GetRightPose();
  420. Ow1 = mpCurrentKeyFrame->GetRightCameraCenter();
  421. sophTcw2 = pKF2->GetRightPose();
  422. Ow2 = pKF2->GetRightCameraCenter();
  423. pCamera1 = mpCurrentKeyFrame->mpCamera2;
  424. pCamera2 = pKF2->mpCamera2;
  425. }
  426. else if(bRight1 && !bRight2){
  427. sophTcw1 = mpCurrentKeyFrame->GetRightPose();
  428. Ow1 = mpCurrentKeyFrame->GetRightCameraCenter();
  429. sophTcw2 = pKF2->GetPose();
  430. Ow2 = pKF2->GetCameraCenter();
  431. pCamera1 = mpCurrentKeyFrame->mpCamera2;
  432. pCamera2 = pKF2->mpCamera;
  433. }
  434. else if(!bRight1 && bRight2){
  435. sophTcw1 = mpCurrentKeyFrame->GetPose();
  436. Ow1 = mpCurrentKeyFrame->GetCameraCenter();
  437. sophTcw2 = pKF2->GetRightPose();
  438. Ow2 = pKF2->GetRightCameraCenter();
  439. pCamera1 = mpCurrentKeyFrame->mpCamera;
  440. pCamera2 = pKF2->mpCamera2;
  441. }
  442. else{
  443. sophTcw1 = mpCurrentKeyFrame->GetPose();
  444. Ow1 = mpCurrentKeyFrame->GetCameraCenter();
  445. sophTcw2 = pKF2->GetPose();
  446. Ow2 = pKF2->GetCameraCenter();
  447. pCamera1 = mpCurrentKeyFrame->mpCamera;
  448. pCamera2 = pKF2->mpCamera;
  449. }
  450. eigTcw1 = sophTcw1.matrix3x4();
  451. Rcw1 = eigTcw1.block<3,3>(0,0);
  452. Rwc1 = Rcw1.transpose();
  453. tcw1 = sophTcw1.translation();
  454. eigTcw2 = sophTcw2.matrix3x4();
  455. Rcw2 = eigTcw2.block<3,3>(0,0);
  456. Rwc2 = Rcw2.transpose();
  457. tcw2 = sophTcw2.translation();
  458. }
  459. // Check parallax between rays
  460. Eigen::Vector3f xn1 = pCamera1->unprojectEig(kp1.pt);
  461. Eigen::Vector3f xn2 = pCamera2->unprojectEig(kp2.pt);
  462. Eigen::Vector3f ray1 = Rwc1 * xn1;
  463. Eigen::Vector3f ray2 = Rwc2 * xn2;
  464. const float cosParallaxRays = ray1.dot(ray2)/(ray1.norm() * ray2.norm());
  465. float cosParallaxStereo = cosParallaxRays+1;
  466. float cosParallaxStereo1 = cosParallaxStereo;
  467. float cosParallaxStereo2 = cosParallaxStereo;
  468. if(bStereo1)
  469. cosParallaxStereo1 = cos(2*atan2(mpCurrentKeyFrame->mb/2,mpCurrentKeyFrame->mvDepth[idx1]));
  470. else if(bStereo2)
  471. cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2]));
  472. if (bStereo1 || bStereo2) totalStereoPts++;
  473. cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2);
  474. Eigen::Vector3f x3D;
  475. bool goodProj = false;
  476. bool bPointStereo = false;
  477. if(cosParallaxRays<cosParallaxStereo && cosParallaxRays>0 && (bStereo1 || bStereo2 ||
  478. (cosParallaxRays<0.9996 && mbInertial) || (cosParallaxRays<0.9998 && !mbInertial)))
  479. {
  480. goodProj = GeometricTools::Triangulate(xn1, xn2, eigTcw1, eigTcw2, x3D);
  481. if(!goodProj)
  482. continue;
  483. }
  484. else if(bStereo1 && cosParallaxStereo1<cosParallaxStereo2)
  485. {
  486. countStereoAttempt++;
  487. bPointStereo = true;
  488. goodProj = mpCurrentKeyFrame->UnprojectStereo(idx1, x3D);
  489. }
  490. else if(bStereo2 && cosParallaxStereo2<cosParallaxStereo1)
  491. {
  492. countStereoAttempt++;
  493. bPointStereo = true;
  494. goodProj = pKF2->UnprojectStereo(idx2, x3D);
  495. }
  496. else
  497. {
  498. continue; //No stereo and very low parallax
  499. }
  500. if(goodProj && bPointStereo)
  501. countStereoGoodProj++;
  502. if(!goodProj)
  503. continue;
  504. //Check triangulation in front of cameras
  505. float z1 = Rcw1.row(2).dot(x3D) + tcw1(2);
  506. if(z1<=0)
  507. continue;
  508. float z2 = Rcw2.row(2).dot(x3D) + tcw2(2);
  509. if(z2<=0)
  510. continue;
  511. //Check reprojection error in first keyframe
  512. const float &sigmaSquare1 = mpCurrentKeyFrame->mvLevelSigma2[kp1.octave];
  513. const float x1 = Rcw1.row(0).dot(x3D)+tcw1(0);
  514. const float y1 = Rcw1.row(1).dot(x3D)+tcw1(1);
  515. const float invz1 = 1.0/z1;
  516. if(!bStereo1)
  517. {
  518. cv::Point2f uv1 = pCamera1->project(cv::Point3f(x1,y1,z1));
  519. float errX1 = uv1.x - kp1.pt.x;
  520. float errY1 = uv1.y - kp1.pt.y;
  521. if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1)
  522. continue;
  523. }
  524. else
  525. {
  526. float u1 = fx1*x1*invz1+cx1;
  527. float u1_r = u1 - mpCurrentKeyFrame->mbf*invz1;
  528. float v1 = fy1*y1*invz1+cy1;
  529. float errX1 = u1 - kp1.pt.x;
  530. float errY1 = v1 - kp1.pt.y;
  531. float errX1_r = u1_r - kp1_ur;
  532. if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1)
  533. continue;
  534. }
  535. //Check reprojection error in second keyframe
  536. const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave];
  537. const float x2 = Rcw2.row(0).dot(x3D)+tcw2(0);
  538. const float y2 = Rcw2.row(1).dot(x3D)+tcw2(1);
  539. const float invz2 = 1.0/z2;
  540. if(!bStereo2)
  541. {
  542. cv::Point2f uv2 = pCamera2->project(cv::Point3f(x2,y2,z2));
  543. float errX2 = uv2.x - kp2.pt.x;
  544. float errY2 = uv2.y - kp2.pt.y;
  545. if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2)
  546. continue;
  547. }
  548. else
  549. {
  550. float u2 = fx2*x2*invz2+cx2;
  551. float u2_r = u2 - mpCurrentKeyFrame->mbf*invz2;
  552. float v2 = fy2*y2*invz2+cy2;
  553. float errX2 = u2 - kp2.pt.x;
  554. float errY2 = v2 - kp2.pt.y;
  555. float errX2_r = u2_r - kp2_ur;
  556. if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2)
  557. continue;
  558. }
  559. //Check scale consistency
  560. Eigen::Vector3f normal1 = x3D - Ow1;
  561. float dist1 = normal1.norm();
  562. Eigen::Vector3f normal2 = x3D - Ow2;
  563. float dist2 = normal2.norm();
  564. if(dist1==0 || dist2==0)
  565. continue;
  566. if(mbFarPoints && (dist1>=mThFarPoints||dist2>=mThFarPoints)) // MODIFICATION
  567. continue;
  568. const float ratioDist = dist2/dist1;
  569. const float ratioOctave = mpCurrentKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave];
  570. if(ratioDist*ratioFactor<ratioOctave || ratioDist>ratioOctave*ratioFactor)
  571. continue;
  572. // Triangulation is succesfull
  573. MapPoint* pMP = new MapPoint(x3D, mpCurrentKeyFrame, mpAtlas->GetCurrentMap());
  574. if (bPointStereo)
  575. countStereo++;
  576. pMP->AddObservation(mpCurrentKeyFrame,idx1);
  577. pMP->AddObservation(pKF2,idx2);
  578. mpCurrentKeyFrame->AddMapPoint(pMP,idx1);
  579. pKF2->AddMapPoint(pMP,idx2);
  580. pMP->ComputeDistinctiveDescriptors();
  581. pMP->UpdateNormalAndDepth();
  582. mpAtlas->AddMapPoint(pMP);
  583. mlpRecentAddedMapPoints.push_back(pMP);
  584. }
  585. }
  586. }
  587. void LocalMapping::SearchInNeighbors()
  588. {
  589. // Retrieve neighbor keyframes
  590. int nn = 10;
  591. if(mbMonocular)
  592. nn=30;
  593. const vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);
  594. vector<KeyFrame*> vpTargetKFs;
  595. for(vector<KeyFrame*>::const_iterator vit=vpNeighKFs.begin(), vend=vpNeighKFs.end(); vit!=vend; vit++)
  596. {
  597. KeyFrame* pKFi = *vit;
  598. if(pKFi->isBad() || pKFi->mnFuseTargetForKF == mpCurrentKeyFrame->mnId)
  599. continue;
  600. vpTargetKFs.push_back(pKFi);
  601. pKFi->mnFuseTargetForKF = mpCurrentKeyFrame->mnId;
  602. }
  603. // Add some covisible of covisible
  604. // Extend to some second neighbors if abort is not requested
  605. for(int i=0, imax=vpTargetKFs.size(); i<imax; i++)
  606. {
  607. const vector<KeyFrame*> vpSecondNeighKFs = vpTargetKFs[i]->GetBestCovisibilityKeyFrames(20);
  608. for(vector<KeyFrame*>::const_iterator vit2=vpSecondNeighKFs.begin(), vend2=vpSecondNeighKFs.end(); vit2!=vend2; vit2++)
  609. {
  610. KeyFrame* pKFi2 = *vit2;
  611. if(pKFi2->isBad() || pKFi2->mnFuseTargetForKF==mpCurrentKeyFrame->mnId || pKFi2->mnId==mpCurrentKeyFrame->mnId)
  612. continue;
  613. vpTargetKFs.push_back(pKFi2);
  614. pKFi2->mnFuseTargetForKF=mpCurrentKeyFrame->mnId;
  615. }
  616. if (mbAbortBA)
  617. break;
  618. }
  619. // Extend to temporal neighbors
  620. if(mbInertial)
  621. {
  622. KeyFrame* pKFi = mpCurrentKeyFrame->mPrevKF;
  623. while(vpTargetKFs.size()<20 && pKFi)
  624. {
  625. if(pKFi->isBad() || pKFi->mnFuseTargetForKF==mpCurrentKeyFrame->mnId)
  626. {
  627. pKFi = pKFi->mPrevKF;
  628. continue;
  629. }
  630. vpTargetKFs.push_back(pKFi);
  631. pKFi->mnFuseTargetForKF=mpCurrentKeyFrame->mnId;
  632. pKFi = pKFi->mPrevKF;
  633. }
  634. }
  635. // Search matches by projection from current KF in target KFs
  636. ORBmatcher matcher;
  637. vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
  638. for(vector<KeyFrame*>::iterator vit=vpTargetKFs.begin(), vend=vpTargetKFs.end(); vit!=vend; vit++)
  639. {
  640. KeyFrame* pKFi = *vit;
  641. matcher.Fuse(pKFi,vpMapPointMatches);
  642. if(pKFi->NLeft != -1) matcher.Fuse(pKFi,vpMapPointMatches,true);
  643. }
  644. if (mbAbortBA)
  645. return;
  646. // Search matches by projection from target KFs in current KF
  647. vector<MapPoint*> vpFuseCandidates;
  648. vpFuseCandidates.reserve(vpTargetKFs.size()*vpMapPointMatches.size());
  649. for(vector<KeyFrame*>::iterator vitKF=vpTargetKFs.begin(), vendKF=vpTargetKFs.end(); vitKF!=vendKF; vitKF++)
  650. {
  651. KeyFrame* pKFi = *vitKF;
  652. vector<MapPoint*> vpMapPointsKFi = pKFi->GetMapPointMatches();
  653. for(vector<MapPoint*>::iterator vitMP=vpMapPointsKFi.begin(), vendMP=vpMapPointsKFi.end(); vitMP!=vendMP; vitMP++)
  654. {
  655. MapPoint* pMP = *vitMP;
  656. if(!pMP)
  657. continue;
  658. if(pMP->isBad() || pMP->mnFuseCandidateForKF == mpCurrentKeyFrame->mnId)
  659. continue;
  660. pMP->mnFuseCandidateForKF = mpCurrentKeyFrame->mnId;
  661. vpFuseCandidates.push_back(pMP);
  662. }
  663. }
  664. matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates);
  665. if(mpCurrentKeyFrame->NLeft != -1) matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates,true);
  666. // Update points
  667. vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
  668. for(size_t i=0, iend=vpMapPointMatches.size(); i<iend; i++)
  669. {
  670. MapPoint* pMP=vpMapPointMatches[i];
  671. if(pMP)
  672. {
  673. if(!pMP->isBad())
  674. {
  675. pMP->ComputeDistinctiveDescriptors();
  676. pMP->UpdateNormalAndDepth();
  677. }
  678. }
  679. }
  680. // Update connections in covisibility graph
  681. mpCurrentKeyFrame->UpdateConnections();
  682. }
  683. void LocalMapping::RequestStop()
  684. {
  685. unique_lock<mutex> lock(mMutexStop);
  686. mbStopRequested = true;
  687. unique_lock<mutex> lock2(mMutexNewKFs);
  688. mbAbortBA = true;
  689. }
  690. bool LocalMapping::Stop()
  691. {
  692. unique_lock<mutex> lock(mMutexStop);
  693. if(mbStopRequested && !mbNotStop)
  694. {
  695. mbStopped = true;
  696. cout << "Local Mapping STOP" << endl;
  697. return true;
  698. }
  699. return false;
  700. }
  701. bool LocalMapping::isStopped()
  702. {
  703. unique_lock<mutex> lock(mMutexStop);
  704. return mbStopped;
  705. }
  706. bool LocalMapping::stopRequested()
  707. {
  708. unique_lock<mutex> lock(mMutexStop);
  709. return mbStopRequested;
  710. }
  711. void LocalMapping::Release()
  712. {
  713. unique_lock<mutex> lock(mMutexStop);
  714. unique_lock<mutex> lock2(mMutexFinish);
  715. if(mbFinished)
  716. return;
  717. mbStopped = false;
  718. mbStopRequested = false;
  719. for(list<KeyFrame*>::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++)
  720. delete *lit;
  721. mlNewKeyFrames.clear();
  722. cout << "Local Mapping RELEASE" << endl;
  723. }
  724. bool LocalMapping::AcceptKeyFrames()
  725. {
  726. unique_lock<mutex> lock(mMutexAccept);
  727. return mbAcceptKeyFrames;
  728. }
  729. void LocalMapping::SetAcceptKeyFrames(bool flag)
  730. {
  731. unique_lock<mutex> lock(mMutexAccept);
  732. mbAcceptKeyFrames=flag;
  733. }
  734. bool LocalMapping::SetNotStop(bool flag)
  735. {
  736. unique_lock<mutex> lock(mMutexStop);
  737. if(flag && mbStopped)
  738. return false;
  739. mbNotStop = flag;
  740. return true;
  741. }
  742. void LocalMapping::InterruptBA()
  743. {
  744. mbAbortBA = true;
  745. }
  746. void LocalMapping::KeyFrameCulling()
  747. {
  748. // Check redundant keyframes (only local keyframes)
  749. // A keyframe is considered redundant if the 90% of the MapPoints it sees, are seen
  750. // in at least other 3 keyframes (in the same or finer scale)
  751. // We only consider close stereo points
  752. const int Nd = 21;
  753. mpCurrentKeyFrame->UpdateBestCovisibles();
  754. vector<KeyFrame*> vpLocalKeyFrames = mpCurrentKeyFrame->GetVectorCovisibleKeyFrames();
  755. float redundant_th;
  756. if(!mbInertial)
  757. redundant_th = 0.9;
  758. else if (mbMonocular)
  759. redundant_th = 0.9;
  760. else
  761. redundant_th = 0.5;
  762. const bool bInitImu = mpAtlas->isImuInitialized();
  763. int count=0;
  764. // Compoute last KF from optimizable window:
  765. unsigned int last_ID;
  766. if (mbInertial)
  767. {
  768. int count = 0;
  769. KeyFrame* aux_KF = mpCurrentKeyFrame;
  770. while(count<Nd && aux_KF->mPrevKF)
  771. {
  772. aux_KF = aux_KF->mPrevKF;
  773. count++;
  774. }
  775. last_ID = aux_KF->mnId;
  776. }
  777. for(vector<KeyFrame*>::iterator vit=vpLocalKeyFrames.begin(), vend=vpLocalKeyFrames.end(); vit!=vend; vit++)
  778. {
  779. count++;
  780. KeyFrame* pKF = *vit;
  781. if((pKF->mnId==pKF->GetMap()->GetInitKFid()) || pKF->isBad())
  782. continue;
  783. const vector<MapPoint*> vpMapPoints = pKF->GetMapPointMatches();
  784. int nObs = 3;
  785. const int thObs=nObs;
  786. int nRedundantObservations=0;
  787. int nMPs=0;
  788. for(size_t i=0, iend=vpMapPoints.size(); i<iend; i++)
  789. {
  790. MapPoint* pMP = vpMapPoints[i];
  791. if(pMP)
  792. {
  793. if(!pMP->isBad())
  794. {
  795. if(!mbMonocular)
  796. {
  797. if(pKF->mvDepth[i]>pKF->mThDepth || pKF->mvDepth[i]<0)
  798. continue;
  799. }
  800. nMPs++;
  801. if(pMP->Observations()>thObs)
  802. {
  803. const int &scaleLevel = (pKF -> NLeft == -1) ? pKF->mvKeysUn[i].octave
  804. : (i < pKF -> NLeft) ? pKF -> mvKeys[i].octave
  805. : pKF -> mvKeysRight[i].octave;
  806. const map<KeyFrame*, tuple<int,int>> observations = pMP->GetObservations();
  807. int nObs=0;
  808. for(map<KeyFrame*, tuple<int,int>>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  809. {
  810. KeyFrame* pKFi = mit->first;
  811. if(pKFi==pKF)
  812. continue;
  813. tuple<int,int> indexes = mit->second;
  814. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  815. int scaleLeveli = -1;
  816. if(pKFi -> NLeft == -1)
  817. scaleLeveli = pKFi->mvKeysUn[leftIndex].octave;
  818. else {
  819. if (leftIndex != -1) {
  820. scaleLeveli = pKFi->mvKeys[leftIndex].octave;
  821. }
  822. if (rightIndex != -1) {
  823. int rightLevel = pKFi->mvKeysRight[rightIndex - pKFi->NLeft].octave;
  824. scaleLeveli = (scaleLeveli == -1 || scaleLeveli > rightLevel) ? rightLevel
  825. : scaleLeveli;
  826. }
  827. }
  828. if(scaleLeveli<=scaleLevel+1)
  829. {
  830. nObs++;
  831. if(nObs>thObs)
  832. break;
  833. }
  834. }
  835. if(nObs>thObs)
  836. {
  837. nRedundantObservations++;
  838. }
  839. }
  840. }
  841. }
  842. }
  843. if(nRedundantObservations>redundant_th*nMPs)
  844. {
  845. if (mbInertial)
  846. {
  847. if (mpAtlas->KeyFramesInMap()<=Nd)
  848. continue;
  849. if(pKF->mnId>(mpCurrentKeyFrame->mnId-2))
  850. continue;
  851. if(pKF->mPrevKF && pKF->mNextKF)
  852. {
  853. const float t = pKF->mNextKF->mTimeStamp-pKF->mPrevKF->mTimeStamp;
  854. if((bInitImu && (pKF->mnId<last_ID) && t<3.) || (t<0.5))
  855. {
  856. pKF->mNextKF->mpImuPreintegrated->MergePrevious(pKF->mpImuPreintegrated);
  857. pKF->mNextKF->mPrevKF = pKF->mPrevKF;
  858. pKF->mPrevKF->mNextKF = pKF->mNextKF;
  859. pKF->mNextKF = NULL;
  860. pKF->mPrevKF = NULL;
  861. pKF->SetBadFlag();
  862. }
  863. else if(!mpCurrentKeyFrame->GetMap()->GetIniertialBA2() && ((pKF->GetImuPosition()-pKF->mPrevKF->GetImuPosition()).norm()<0.02) && (t<3))
  864. {
  865. pKF->mNextKF->mpImuPreintegrated->MergePrevious(pKF->mpImuPreintegrated);
  866. pKF->mNextKF->mPrevKF = pKF->mPrevKF;
  867. pKF->mPrevKF->mNextKF = pKF->mNextKF;
  868. pKF->mNextKF = NULL;
  869. pKF->mPrevKF = NULL;
  870. pKF->SetBadFlag();
  871. }
  872. }
  873. }
  874. else
  875. {
  876. pKF->SetBadFlag();
  877. }
  878. }
  879. if((count > 20 && mbAbortBA) || count>100)
  880. {
  881. break;
  882. }
  883. }
  884. }
  885. void LocalMapping::RequestReset()
  886. {
  887. {
  888. unique_lock<mutex> lock(mMutexReset);
  889. cout << "LM: Map reset recieved" << endl;
  890. mbResetRequested = true;
  891. }
  892. cout << "LM: Map reset, waiting..." << endl;
  893. while(1)
  894. {
  895. {
  896. unique_lock<mutex> lock2(mMutexReset);
  897. if(!mbResetRequested)
  898. break;
  899. }
  900. usleep(3000);
  901. }
  902. cout << "LM: Map reset, Done!!!" << endl;
  903. }
  904. void LocalMapping::RequestResetActiveMap(Map* pMap)
  905. {
  906. {
  907. unique_lock<mutex> lock(mMutexReset);
  908. cout << "LM: Active map reset recieved" << endl;
  909. mbResetRequestedActiveMap = true;
  910. mpMapToReset = pMap;
  911. }
  912. cout << "LM: Active map reset, waiting..." << endl;
  913. while(1)
  914. {
  915. {
  916. unique_lock<mutex> lock2(mMutexReset);
  917. if(!mbResetRequestedActiveMap)
  918. break;
  919. }
  920. usleep(3000);
  921. }
  922. cout << "LM: Active map reset, Done!!!" << endl;
  923. }
  924. void LocalMapping::ResetIfRequested()
  925. {
  926. bool executed_reset = false;
  927. {
  928. unique_lock<mutex> lock(mMutexReset);
  929. if(mbResetRequested)
  930. {
  931. executed_reset = true;
  932. cout << "LM: Reseting Atlas in Local Mapping..." << endl;
  933. mlNewKeyFrames.clear();
  934. mlpRecentAddedMapPoints.clear();
  935. mbResetRequested = false;
  936. mbResetRequestedActiveMap = false;
  937. // Inertial parameters
  938. mTinit = 0.f;
  939. mbNotBA2 = true;
  940. mbNotBA1 = true;
  941. mbBadImu=false;
  942. mIdxInit=0;
  943. cout << "LM: End reseting Local Mapping..." << endl;
  944. }
  945. if(mbResetRequestedActiveMap) {
  946. executed_reset = true;
  947. cout << "LM: Reseting current map in Local Mapping..." << endl;
  948. mlNewKeyFrames.clear();
  949. mlpRecentAddedMapPoints.clear();
  950. // Inertial parameters
  951. mTinit = 0.f;
  952. mbNotBA2 = true;
  953. mbNotBA1 = true;
  954. mbBadImu=false;
  955. mbResetRequested = false;
  956. mbResetRequestedActiveMap = false;
  957. cout << "LM: End reseting Local Mapping..." << endl;
  958. }
  959. }
  960. if(executed_reset)
  961. cout << "LM: Reset free the mutex" << endl;
  962. }
  963. void LocalMapping::RequestFinish()
  964. {
  965. unique_lock<mutex> lock(mMutexFinish);
  966. mbFinishRequested = true;
  967. }
  968. bool LocalMapping::CheckFinish()
  969. {
  970. unique_lock<mutex> lock(mMutexFinish);
  971. return mbFinishRequested;
  972. }
  973. void LocalMapping::SetFinish()
  974. {
  975. unique_lock<mutex> lock(mMutexFinish);
  976. mbFinished = true;
  977. unique_lock<mutex> lock2(mMutexStop);
  978. mbStopped = true;
  979. }
  980. bool LocalMapping::isFinished()
  981. {
  982. unique_lock<mutex> lock(mMutexFinish);
  983. return mbFinished;
  984. }
  985. void LocalMapping::InitializeIMU(float priorG, float priorA, bool bFIBA)
  986. {
  987. if (mbResetRequested)
  988. return;
  989. float minTime;
  990. int nMinKF;
  991. if (mbMonocular)
  992. {
  993. minTime = 2.0;
  994. nMinKF = 10;
  995. }
  996. else
  997. {
  998. minTime = 1.0;
  999. nMinKF = 10;
  1000. }
  1001. if(mpAtlas->KeyFramesInMap()<nMinKF)
  1002. return;
  1003. // Retrieve all keyframe in temporal order
  1004. list<KeyFrame*> lpKF;
  1005. KeyFrame* pKF = mpCurrentKeyFrame;
  1006. while(pKF->mPrevKF)
  1007. {
  1008. lpKF.push_front(pKF);
  1009. pKF = pKF->mPrevKF;
  1010. }
  1011. lpKF.push_front(pKF);
  1012. vector<KeyFrame*> vpKF(lpKF.begin(),lpKF.end());
  1013. if(vpKF.size()<nMinKF)
  1014. return;
  1015. mFirstTs=vpKF.front()->mTimeStamp;
  1016. if(mpCurrentKeyFrame->mTimeStamp-mFirstTs<minTime)
  1017. return;
  1018. bInitializing = true;
  1019. while(CheckNewKeyFrames())
  1020. {
  1021. ProcessNewKeyFrame();
  1022. vpKF.push_back(mpCurrentKeyFrame);
  1023. lpKF.push_back(mpCurrentKeyFrame);
  1024. }
  1025. const int N = vpKF.size();
  1026. IMU::Bias b(0,0,0,0,0,0);
  1027. // Compute and KF velocities mRwg estimation
  1028. if (!mpCurrentKeyFrame->GetMap()->isImuInitialized())
  1029. {
  1030. Eigen::Matrix3f Rwg;
  1031. Eigen::Vector3f dirG;
  1032. dirG.setZero();
  1033. for(vector<KeyFrame*>::iterator itKF = vpKF.begin(); itKF!=vpKF.end(); itKF++)
  1034. {
  1035. if (!(*itKF)->mpImuPreintegrated)
  1036. continue;
  1037. if (!(*itKF)->mPrevKF)
  1038. continue;
  1039. dirG -= (*itKF)->mPrevKF->GetImuRotation() * (*itKF)->mpImuPreintegrated->GetUpdatedDeltaVelocity();
  1040. Eigen::Vector3f _vel = ((*itKF)->GetImuPosition() - (*itKF)->mPrevKF->GetImuPosition())/(*itKF)->mpImuPreintegrated->dT;
  1041. (*itKF)->SetVelocity(_vel);
  1042. (*itKF)->mPrevKF->SetVelocity(_vel);
  1043. }
  1044. dirG = dirG/dirG.norm();
  1045. Eigen::Vector3f gI(0.0f, 0.0f, -1.0f);
  1046. Eigen::Vector3f v = gI.cross(dirG);
  1047. const float nv = v.norm();
  1048. const float cosg = gI.dot(dirG);
  1049. const float ang = acos(cosg);
  1050. Eigen::Vector3f vzg = v*ang/nv;
  1051. Rwg = Sophus::SO3f::exp(vzg).matrix();
  1052. mRwg = Rwg.cast<double>();
  1053. mTinit = mpCurrentKeyFrame->mTimeStamp-mFirstTs;
  1054. }
  1055. else
  1056. {
  1057. mRwg = Eigen::Matrix3d::Identity();
  1058. mbg = mpCurrentKeyFrame->GetGyroBias().cast<double>();
  1059. mba = mpCurrentKeyFrame->GetAccBias().cast<double>();
  1060. }
  1061. mScale=1.0;
  1062. mInitTime = mpTracker->mLastFrame.mTimeStamp-vpKF.front()->mTimeStamp;
  1063. std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now();
  1064. Optimizer::InertialOptimization(mpAtlas->GetCurrentMap(), mRwg, mScale, mbg, mba, mbMonocular, infoInertial, false, false, priorG, priorA);
  1065. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  1066. if (mScale<1e-1)
  1067. {
  1068. cout << "scale too small" << endl;
  1069. bInitializing=false;
  1070. return;
  1071. }
  1072. // Before this line we are not changing the map
  1073. {
  1074. unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
  1075. if ((fabs(mScale - 1.f) > 0.00001) || !mbMonocular) {
  1076. Sophus::SE3f Twg(mRwg.cast<float>().transpose(), Eigen::Vector3f::Zero());
  1077. mpAtlas->GetCurrentMap()->ApplyScaledRotation(Twg, mScale, true);
  1078. mpTracker->UpdateFrameIMU(mScale, vpKF[0]->GetImuBias(), mpCurrentKeyFrame);
  1079. }
  1080. // Check if initialization OK
  1081. if (!mpAtlas->isImuInitialized())
  1082. for (int i = 0; i < N; i++) {
  1083. KeyFrame *pKF2 = vpKF[i];
  1084. pKF2->bImu = true;
  1085. }
  1086. }
  1087. mpTracker->UpdateFrameIMU(1.0,vpKF[0]->GetImuBias(),mpCurrentKeyFrame);
  1088. if (!mpAtlas->isImuInitialized())
  1089. {
  1090. mpAtlas->SetImuInitialized();
  1091. mpTracker->t0IMU = mpTracker->mCurrentFrame.mTimeStamp;
  1092. mpCurrentKeyFrame->bImu = true;
  1093. }
  1094. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  1095. if (bFIBA)
  1096. {
  1097. if (priorA!=0.f)
  1098. Optimizer::FullInertialBA(mpAtlas->GetCurrentMap(), 100, false, mpCurrentKeyFrame->mnId, NULL, true, priorG, priorA);
  1099. else
  1100. Optimizer::FullInertialBA(mpAtlas->GetCurrentMap(), 100, false, mpCurrentKeyFrame->mnId, NULL, false);
  1101. }
  1102. std::chrono::steady_clock::time_point t5 = std::chrono::steady_clock::now();
  1103. Verbose::PrintMess("Global Bundle Adjustment finished\nUpdating map ...", Verbose::VERBOSITY_NORMAL);
  1104. // Get Map Mutex
  1105. unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
  1106. unsigned long GBAid = mpCurrentKeyFrame->mnId;
  1107. // Process keyframes in the queue
  1108. while(CheckNewKeyFrames())
  1109. {
  1110. ProcessNewKeyFrame();
  1111. vpKF.push_back(mpCurrentKeyFrame);
  1112. lpKF.push_back(mpCurrentKeyFrame);
  1113. }
  1114. // Correct keyframes starting at map first keyframe
  1115. list<KeyFrame*> lpKFtoCheck(mpAtlas->GetCurrentMap()->mvpKeyFrameOrigins.begin(),mpAtlas->GetCurrentMap()->mvpKeyFrameOrigins.end());
  1116. while(!lpKFtoCheck.empty())
  1117. {
  1118. KeyFrame* pKF = lpKFtoCheck.front();
  1119. const set<KeyFrame*> sChilds = pKF->GetChilds();
  1120. Sophus::SE3f Twc = pKF->GetPoseInverse();
  1121. for(set<KeyFrame*>::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++)
  1122. {
  1123. KeyFrame* pChild = *sit;
  1124. if(!pChild || pChild->isBad())
  1125. continue;
  1126. if(pChild->mnBAGlobalForKF!=GBAid)
  1127. {
  1128. Sophus::SE3f Tchildc = pChild->GetPose() * Twc;
  1129. pChild->mTcwGBA = Tchildc * pKF->mTcwGBA;
  1130. Sophus::SO3f Rcor = pChild->mTcwGBA.so3().inverse() * pChild->GetPose().so3();
  1131. if(pChild->isVelocitySet()){
  1132. pChild->mVwbGBA = Rcor * pChild->GetVelocity();
  1133. }
  1134. else {
  1135. Verbose::PrintMess("Child velocity empty!! ", Verbose::VERBOSITY_NORMAL);
  1136. }
  1137. pChild->mBiasGBA = pChild->GetImuBias();
  1138. pChild->mnBAGlobalForKF = GBAid;
  1139. }
  1140. lpKFtoCheck.push_back(pChild);
  1141. }
  1142. pKF->mTcwBefGBA = pKF->GetPose();
  1143. pKF->SetPose(pKF->mTcwGBA);
  1144. if(pKF->bImu)
  1145. {
  1146. pKF->mVwbBefGBA = pKF->GetVelocity();
  1147. pKF->SetVelocity(pKF->mVwbGBA);
  1148. pKF->SetNewBias(pKF->mBiasGBA);
  1149. } else {
  1150. cout << "KF " << pKF->mnId << " not set to inertial!! \n";
  1151. }
  1152. lpKFtoCheck.pop_front();
  1153. }
  1154. // Correct MapPoints
  1155. const vector<MapPoint*> vpMPs = mpAtlas->GetCurrentMap()->GetAllMapPoints();
  1156. for(size_t i=0; i<vpMPs.size(); i++)
  1157. {
  1158. MapPoint* pMP = vpMPs[i];
  1159. if(pMP->isBad())
  1160. continue;
  1161. if(pMP->mnBAGlobalForKF==GBAid)
  1162. {
  1163. // If optimized by Global BA, just update
  1164. pMP->SetWorldPos(pMP->mPosGBA);
  1165. }
  1166. else
  1167. {
  1168. // Update according to the correction of its reference keyframe
  1169. KeyFrame* pRefKF = pMP->GetReferenceKeyFrame();
  1170. if(pRefKF->mnBAGlobalForKF!=GBAid)
  1171. continue;
  1172. // Map to non-corrected camera
  1173. Eigen::Vector3f Xc = pRefKF->mTcwBefGBA * pMP->GetWorldPos();
  1174. // Backproject using corrected camera
  1175. pMP->SetWorldPos(pRefKF->GetPoseInverse() * Xc);
  1176. }
  1177. }
  1178. Verbose::PrintMess("Map updated!", Verbose::VERBOSITY_NORMAL);
  1179. mnKFs=vpKF.size();
  1180. mIdxInit++;
  1181. for(list<KeyFrame*>::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++)
  1182. {
  1183. (*lit)->SetBadFlag();
  1184. delete *lit;
  1185. }
  1186. mlNewKeyFrames.clear();
  1187. mpTracker->mState=Tracking::OK;
  1188. bInitializing = false;
  1189. mpCurrentKeyFrame->GetMap()->IncreaseChangeIndex();
  1190. return;
  1191. }
  1192. void LocalMapping::ScaleRefinement()
  1193. {
  1194. // Minimum number of keyframes to compute a solution
  1195. // Minimum time (seconds) between first and last keyframe to compute a solution. Make the difference between monocular and stereo
  1196. // unique_lock<mutex> lock0(mMutexImuInit);
  1197. if (mbResetRequested)
  1198. return;
  1199. // Retrieve all keyframes in temporal order
  1200. list<KeyFrame*> lpKF;
  1201. KeyFrame* pKF = mpCurrentKeyFrame;
  1202. while(pKF->mPrevKF)
  1203. {
  1204. lpKF.push_front(pKF);
  1205. pKF = pKF->mPrevKF;
  1206. }
  1207. lpKF.push_front(pKF);
  1208. vector<KeyFrame*> vpKF(lpKF.begin(),lpKF.end());
  1209. while(CheckNewKeyFrames())
  1210. {
  1211. ProcessNewKeyFrame();
  1212. vpKF.push_back(mpCurrentKeyFrame);
  1213. lpKF.push_back(mpCurrentKeyFrame);
  1214. }
  1215. const int N = vpKF.size();
  1216. mRwg = Eigen::Matrix3d::Identity();
  1217. mScale=1.0;
  1218. std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now();
  1219. Optimizer::InertialOptimization(mpAtlas->GetCurrentMap(), mRwg, mScale);
  1220. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  1221. if (mScale<1e-1) // 1e-1
  1222. {
  1223. cout << "scale too small" << endl;
  1224. bInitializing=false;
  1225. return;
  1226. }
  1227. Sophus::SO3d so3wg(mRwg);
  1228. // Before this line we are not changing the map
  1229. unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
  1230. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  1231. if ((fabs(mScale-1.f)>0.002)||!mbMonocular)
  1232. {
  1233. Sophus::SE3f Tgw(mRwg.cast<float>().transpose(),Eigen::Vector3f::Zero());
  1234. mpAtlas->GetCurrentMap()->ApplyScaledRotation(Tgw,mScale,true);
  1235. mpTracker->UpdateFrameIMU(mScale,mpCurrentKeyFrame->GetImuBias(),mpCurrentKeyFrame);
  1236. }
  1237. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  1238. for(list<KeyFrame*>::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++)
  1239. {
  1240. (*lit)->SetBadFlag();
  1241. delete *lit;
  1242. }
  1243. mlNewKeyFrames.clear();
  1244. double t_inertial_only = std::chrono::duration_cast<std::chrono::duration<double> >(t1 - t0).count();
  1245. // To perform pose-inertial opt w.r.t. last keyframe
  1246. mpCurrentKeyFrame->GetMap()->IncreaseChangeIndex();
  1247. return;
  1248. }
  1249. bool LocalMapping::IsInitializing()
  1250. {
  1251. return bInitializing;
  1252. }
  1253. double LocalMapping::GetCurrKFTime()
  1254. {
  1255. if (mpCurrentKeyFrame)
  1256. {
  1257. return mpCurrentKeyFrame->mTimeStamp;
  1258. }
  1259. else
  1260. return 0.0;
  1261. }
  1262. KeyFrame* LocalMapping::GetCurrKF()
  1263. {
  1264. return mpCurrentKeyFrame;
  1265. }
  1266. } //namespace ORB_SLAM