LoopClosing.cc 95 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422242324242425242624272428242924302431243224332434243524362437243824392440244124422443244424452446244724482449245024512452245324542455245624572458245924602461246224632464246524662467246824692470247124722473247424752476247724782479248024812482248324842485248624872488248924902491249224932494249524962497249824992500250125022503250425052506250725082509251025112512251325142515251625172518251925202521252225232524252525262527252825292530253125322533253425352536253725382539
  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 "LoopClosing.h"
  19. #include "Sim3Solver.h"
  20. #include "Converter.h"
  21. #include "Optimizer.h"
  22. #include "ORBmatcher.h"
  23. #include "G2oTypes.h"
  24. #include<mutex>
  25. #include<thread>
  26. namespace ORB_SLAM3
  27. {
  28. LoopClosing::LoopClosing(Atlas *pAtlas, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale, const bool bActiveLC):
  29. mbResetRequested(false), mbResetActiveMapRequested(false), mbFinishRequested(false), mbFinished(true), mpAtlas(pAtlas),
  30. mpKeyFrameDB(pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL), mLastLoopKFid(0), mbRunningGBA(false), mbFinishedGBA(true),
  31. mbStopGBA(false), mpThreadGBA(NULL), mbFixScale(bFixScale), mnFullBAIdx(0), mnLoopNumCoincidences(0), mnMergeNumCoincidences(0),
  32. mbLoopDetected(false), mbMergeDetected(false), mnLoopNumNotFound(0), mnMergeNumNotFound(0), mbActiveLC(bActiveLC)
  33. {
  34. mnCovisibilityConsistencyTh = 3;
  35. mpLastCurrentKF = static_cast<KeyFrame*>(NULL);
  36. #ifdef REGISTER_TIMES
  37. vdDataQuery_ms.clear();
  38. vdEstSim3_ms.clear();
  39. vdPRTotal_ms.clear();
  40. vdMergeMaps_ms.clear();
  41. vdWeldingBA_ms.clear();
  42. vdMergeOptEss_ms.clear();
  43. vdMergeTotal_ms.clear();
  44. vnMergeKFs.clear();
  45. vnMergeMPs.clear();
  46. nMerges = 0;
  47. vdLoopFusion_ms.clear();
  48. vdLoopOptEss_ms.clear();
  49. vdLoopTotal_ms.clear();
  50. vnLoopKFs.clear();
  51. nLoop = 0;
  52. vdGBA_ms.clear();
  53. vdUpdateMap_ms.clear();
  54. vdFGBATotal_ms.clear();
  55. vnGBAKFs.clear();
  56. vnGBAMPs.clear();
  57. nFGBA_exec = 0;
  58. nFGBA_abort = 0;
  59. #endif
  60. mstrFolderSubTraj = "SubTrajectories/";
  61. mnNumCorrection = 0;
  62. mnCorrectionGBA = 0;
  63. }
  64. void LoopClosing::SetTracker(Tracking *pTracker)
  65. {
  66. mpTracker=pTracker;
  67. }
  68. void LoopClosing::SetLocalMapper(LocalMapping *pLocalMapper)
  69. {
  70. mpLocalMapper=pLocalMapper;
  71. }
  72. void LoopClosing::Run()
  73. {
  74. mbFinished =false;
  75. while(1)
  76. {
  77. //NEW LOOP AND MERGE DETECTION ALGORITHM
  78. //----------------------------
  79. if(CheckNewKeyFrames())
  80. {
  81. if(mpLastCurrentKF)
  82. {
  83. mpLastCurrentKF->mvpLoopCandKFs.clear();
  84. mpLastCurrentKF->mvpMergeCandKFs.clear();
  85. }
  86. #ifdef REGISTER_TIMES
  87. std::chrono::steady_clock::time_point time_StartPR = std::chrono::steady_clock::now();
  88. #endif
  89. bool bFindedRegion = NewDetectCommonRegions();
  90. #ifdef REGISTER_TIMES
  91. std::chrono::steady_clock::time_point time_EndPR = std::chrono::steady_clock::now();
  92. double timePRTotal = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndPR - time_StartPR).count();
  93. vdPRTotal_ms.push_back(timePRTotal);
  94. #endif
  95. if(bFindedRegion)
  96. {
  97. if(mbMergeDetected)
  98. {
  99. if ((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD) &&
  100. (!mpCurrentKF->GetMap()->isImuInitialized()))
  101. {
  102. cout << "IMU is not initilized, merge is aborted" << endl;
  103. }
  104. else
  105. {
  106. Sophus::SE3d mTmw = mpMergeMatchedKF->GetPose().cast<double>();
  107. g2o::Sim3 gSmw2(mTmw.unit_quaternion(), mTmw.translation(), 1.0);
  108. Sophus::SE3d mTcw = mpCurrentKF->GetPose().cast<double>();
  109. g2o::Sim3 gScw1(mTcw.unit_quaternion(), mTcw.translation(), 1.0);
  110. g2o::Sim3 gSw2c = mg2oMergeSlw.inverse();
  111. g2o::Sim3 gSw1m = mg2oMergeSlw;
  112. mSold_new = (gSw2c * gScw1);
  113. if(mpCurrentKF->GetMap()->IsInertial() && mpMergeMatchedKF->GetMap()->IsInertial())
  114. {
  115. cout << "Merge check transformation with IMU" << endl;
  116. if(mSold_new.scale()<0.90||mSold_new.scale()>1.1){
  117. mpMergeLastCurrentKF->SetErase();
  118. mpMergeMatchedKF->SetErase();
  119. mnMergeNumCoincidences = 0;
  120. mvpMergeMatchedMPs.clear();
  121. mvpMergeMPs.clear();
  122. mnMergeNumNotFound = 0;
  123. mbMergeDetected = false;
  124. Verbose::PrintMess("scale bad estimated. Abort merging", Verbose::VERBOSITY_NORMAL);
  125. continue;
  126. }
  127. // If inertial, force only yaw
  128. if ((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD) &&
  129. mpCurrentKF->GetMap()->GetIniertialBA1())
  130. {
  131. Eigen::Vector3d phi = LogSO3(mSold_new.rotation().toRotationMatrix());
  132. phi(0)=0;
  133. phi(1)=0;
  134. mSold_new = g2o::Sim3(ExpSO3(phi),mSold_new.translation(),1.0);
  135. }
  136. }
  137. mg2oMergeSmw = gSmw2 * gSw2c * gScw1;
  138. mg2oMergeScw = mg2oMergeSlw;
  139. //mpTracker->SetStepByStep(true);
  140. Verbose::PrintMess("*Merge detected", Verbose::VERBOSITY_QUIET);
  141. #ifdef REGISTER_TIMES
  142. std::chrono::steady_clock::time_point time_StartMerge = std::chrono::steady_clock::now();
  143. nMerges += 1;
  144. #endif
  145. // TODO UNCOMMENT
  146. if (mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD)
  147. MergeLocal2();
  148. else
  149. MergeLocal();
  150. #ifdef REGISTER_TIMES
  151. std::chrono::steady_clock::time_point time_EndMerge = std::chrono::steady_clock::now();
  152. double timeMergeTotal = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndMerge - time_StartMerge).count();
  153. vdMergeTotal_ms.push_back(timeMergeTotal);
  154. #endif
  155. Verbose::PrintMess("Merge finished!", Verbose::VERBOSITY_QUIET);
  156. }
  157. vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp);
  158. vdPR_MatchedTime.push_back(mpMergeMatchedKF->mTimeStamp);
  159. vnPR_TypeRecogn.push_back(1);
  160. // Reset all variables
  161. mpMergeLastCurrentKF->SetErase();
  162. mpMergeMatchedKF->SetErase();
  163. mnMergeNumCoincidences = 0;
  164. mvpMergeMatchedMPs.clear();
  165. mvpMergeMPs.clear();
  166. mnMergeNumNotFound = 0;
  167. mbMergeDetected = false;
  168. if(mbLoopDetected)
  169. {
  170. // Reset Loop variables
  171. mpLoopLastCurrentKF->SetErase();
  172. mpLoopMatchedKF->SetErase();
  173. mnLoopNumCoincidences = 0;
  174. mvpLoopMatchedMPs.clear();
  175. mvpLoopMPs.clear();
  176. mnLoopNumNotFound = 0;
  177. mbLoopDetected = false;
  178. }
  179. }
  180. if(mbLoopDetected)
  181. {
  182. bool bGoodLoop = true;
  183. vdPR_CurrentTime.push_back(mpCurrentKF->mTimeStamp);
  184. vdPR_MatchedTime.push_back(mpLoopMatchedKF->mTimeStamp);
  185. vnPR_TypeRecogn.push_back(0);
  186. Verbose::PrintMess("*Loop detected", Verbose::VERBOSITY_QUIET);
  187. mg2oLoopScw = mg2oLoopSlw; //*mvg2oSim3LoopTcw[nCurrentIndex];
  188. if(mpCurrentKF->GetMap()->IsInertial())
  189. {
  190. Sophus::SE3d Twc = mpCurrentKF->GetPoseInverse().cast<double>();
  191. g2o::Sim3 g2oTwc(Twc.unit_quaternion(),Twc.translation(),1.0);
  192. g2o::Sim3 g2oSww_new = g2oTwc*mg2oLoopScw;
  193. Eigen::Vector3d phi = LogSO3(g2oSww_new.rotation().toRotationMatrix());
  194. cout << "phi = " << phi.transpose() << endl;
  195. if (fabs(phi(0))<0.008f && fabs(phi(1))<0.008f && fabs(phi(2))<0.349f)
  196. {
  197. if(mpCurrentKF->GetMap()->IsInertial())
  198. {
  199. // If inertial, force only yaw
  200. if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD) &&
  201. mpCurrentKF->GetMap()->GetIniertialBA2())
  202. {
  203. phi(0)=0;
  204. phi(1)=0;
  205. g2oSww_new = g2o::Sim3(ExpSO3(phi),g2oSww_new.translation(),1.0);
  206. mg2oLoopScw = g2oTwc.inverse()*g2oSww_new;
  207. }
  208. }
  209. }
  210. else
  211. {
  212. cout << "BAD LOOP!!!" << endl;
  213. bGoodLoop = false;
  214. }
  215. }
  216. if (bGoodLoop) {
  217. mvpLoopMapPoints = mvpLoopMPs;
  218. #ifdef REGISTER_TIMES
  219. std::chrono::steady_clock::time_point time_StartLoop = std::chrono::steady_clock::now();
  220. nLoop += 1;
  221. #endif
  222. CorrectLoop();
  223. #ifdef REGISTER_TIMES
  224. std::chrono::steady_clock::time_point time_EndLoop = std::chrono::steady_clock::now();
  225. double timeLoopTotal = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndLoop - time_StartLoop).count();
  226. vdLoopTotal_ms.push_back(timeLoopTotal);
  227. #endif
  228. mnNumCorrection += 1;
  229. }
  230. // Reset all variables
  231. mpLoopLastCurrentKF->SetErase();
  232. mpLoopMatchedKF->SetErase();
  233. mnLoopNumCoincidences = 0;
  234. mvpLoopMatchedMPs.clear();
  235. mvpLoopMPs.clear();
  236. mnLoopNumNotFound = 0;
  237. mbLoopDetected = false;
  238. }
  239. }
  240. mpLastCurrentKF = mpCurrentKF;
  241. }
  242. ResetIfRequested();
  243. if(CheckFinish()){
  244. break;
  245. }
  246. usleep(5000);
  247. }
  248. SetFinish();
  249. }
  250. void LoopClosing::InsertKeyFrame(KeyFrame *pKF)
  251. {
  252. unique_lock<mutex> lock(mMutexLoopQueue);
  253. if(pKF->mnId!=0)
  254. mlpLoopKeyFrameQueue.push_back(pKF);
  255. }
  256. bool LoopClosing::CheckNewKeyFrames()
  257. {
  258. unique_lock<mutex> lock(mMutexLoopQueue);
  259. return(!mlpLoopKeyFrameQueue.empty());
  260. }
  261. bool LoopClosing::NewDetectCommonRegions()
  262. {
  263. // To deactivate placerecognition. No loopclosing nor merging will be performed
  264. if(!mbActiveLC)
  265. return false;
  266. {
  267. unique_lock<mutex> lock(mMutexLoopQueue);
  268. mpCurrentKF = mlpLoopKeyFrameQueue.front();
  269. mlpLoopKeyFrameQueue.pop_front();
  270. // Avoid that a keyframe can be erased while it is being process by this thread
  271. mpCurrentKF->SetNotErase();
  272. mpCurrentKF->mbCurrentPlaceRecognition = true;
  273. mpLastMap = mpCurrentKF->GetMap();
  274. }
  275. if(mpLastMap->IsInertial() && !mpLastMap->GetIniertialBA2())
  276. {
  277. mpKeyFrameDB->add(mpCurrentKF);
  278. mpCurrentKF->SetErase();
  279. return false;
  280. }
  281. if(mpTracker->mSensor == System::STEREO && mpLastMap->GetAllKeyFrames().size() < 5) //12
  282. {
  283. // cout << "LoopClousure: Stereo KF inserted without check: " << mpCurrentKF->mnId << endl;
  284. mpKeyFrameDB->add(mpCurrentKF);
  285. mpCurrentKF->SetErase();
  286. return false;
  287. }
  288. if(mpLastMap->GetAllKeyFrames().size() < 12)
  289. {
  290. // cout << "LoopClousure: Stereo KF inserted without check, map is small: " << mpCurrentKF->mnId << endl;
  291. mpKeyFrameDB->add(mpCurrentKF);
  292. mpCurrentKF->SetErase();
  293. return false;
  294. }
  295. //cout << "LoopClousure: Checking KF: " << mpCurrentKF->mnId << endl;
  296. //Check the last candidates with geometric validation
  297. // Loop candidates
  298. bool bLoopDetectedInKF = false;
  299. bool bCheckSpatial = false;
  300. #ifdef REGISTER_TIMES
  301. std::chrono::steady_clock::time_point time_StartEstSim3_1 = std::chrono::steady_clock::now();
  302. #endif
  303. if(mnLoopNumCoincidences > 0)
  304. {
  305. bCheckSpatial = true;
  306. // Find from the last KF candidates
  307. Sophus::SE3d mTcl = (mpCurrentKF->GetPose() * mpLoopLastCurrentKF->GetPoseInverse()).cast<double>();
  308. g2o::Sim3 gScl(mTcl.unit_quaternion(),mTcl.translation(),1.0);
  309. g2o::Sim3 gScw = gScl * mg2oLoopSlw;
  310. int numProjMatches = 0;
  311. vector<MapPoint*> vpMatchedMPs;
  312. bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpLoopMatchedKF, gScw, numProjMatches, mvpLoopMPs, vpMatchedMPs);
  313. if(bCommonRegion)
  314. {
  315. bLoopDetectedInKF = true;
  316. mnLoopNumCoincidences++;
  317. mpLoopLastCurrentKF->SetErase();
  318. mpLoopLastCurrentKF = mpCurrentKF;
  319. mg2oLoopSlw = gScw;
  320. mvpLoopMatchedMPs = vpMatchedMPs;
  321. mbLoopDetected = mnLoopNumCoincidences >= 3;
  322. mnLoopNumNotFound = 0;
  323. if(!mbLoopDetected)
  324. {
  325. cout << "PR: Loop detected with Reffine Sim3" << endl;
  326. }
  327. }
  328. else
  329. {
  330. bLoopDetectedInKF = false;
  331. mnLoopNumNotFound++;
  332. if(mnLoopNumNotFound >= 2)
  333. {
  334. mpLoopLastCurrentKF->SetErase();
  335. mpLoopMatchedKF->SetErase();
  336. mnLoopNumCoincidences = 0;
  337. mvpLoopMatchedMPs.clear();
  338. mvpLoopMPs.clear();
  339. mnLoopNumNotFound = 0;
  340. }
  341. }
  342. }
  343. //Merge candidates
  344. bool bMergeDetectedInKF = false;
  345. if(mnMergeNumCoincidences > 0)
  346. {
  347. // Find from the last KF candidates
  348. Sophus::SE3d mTcl = (mpCurrentKF->GetPose() * mpMergeLastCurrentKF->GetPoseInverse()).cast<double>();
  349. g2o::Sim3 gScl(mTcl.unit_quaternion(), mTcl.translation(), 1.0);
  350. g2o::Sim3 gScw = gScl * mg2oMergeSlw;
  351. int numProjMatches = 0;
  352. vector<MapPoint*> vpMatchedMPs;
  353. bool bCommonRegion = DetectAndReffineSim3FromLastKF(mpCurrentKF, mpMergeMatchedKF, gScw, numProjMatches, mvpMergeMPs, vpMatchedMPs);
  354. if(bCommonRegion)
  355. {
  356. bMergeDetectedInKF = true;
  357. mnMergeNumCoincidences++;
  358. mpMergeLastCurrentKF->SetErase();
  359. mpMergeLastCurrentKF = mpCurrentKF;
  360. mg2oMergeSlw = gScw;
  361. mvpMergeMatchedMPs = vpMatchedMPs;
  362. mbMergeDetected = mnMergeNumCoincidences >= 3;
  363. }
  364. else
  365. {
  366. mbMergeDetected = false;
  367. bMergeDetectedInKF = false;
  368. mnMergeNumNotFound++;
  369. if(mnMergeNumNotFound >= 2)
  370. {
  371. mpMergeLastCurrentKF->SetErase();
  372. mpMergeMatchedKF->SetErase();
  373. mnMergeNumCoincidences = 0;
  374. mvpMergeMatchedMPs.clear();
  375. mvpMergeMPs.clear();
  376. mnMergeNumNotFound = 0;
  377. }
  378. }
  379. }
  380. #ifdef REGISTER_TIMES
  381. std::chrono::steady_clock::time_point time_EndEstSim3_1 = std::chrono::steady_clock::now();
  382. double timeEstSim3 = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndEstSim3_1 - time_StartEstSim3_1).count();
  383. #endif
  384. if(mbMergeDetected || mbLoopDetected)
  385. {
  386. #ifdef REGISTER_TIMES
  387. vdEstSim3_ms.push_back(timeEstSim3);
  388. #endif
  389. mpKeyFrameDB->add(mpCurrentKF);
  390. return true;
  391. }
  392. //TODO: This is only necessary if we use a minimun score for pick the best candidates
  393. const vector<KeyFrame*> vpConnectedKeyFrames = mpCurrentKF->GetVectorCovisibleKeyFrames();
  394. // Extract candidates from the bag of words
  395. vector<KeyFrame*> vpMergeBowCand, vpLoopBowCand;
  396. if(!bMergeDetectedInKF || !bLoopDetectedInKF)
  397. {
  398. // Search in BoW
  399. #ifdef REGISTER_TIMES
  400. std::chrono::steady_clock::time_point time_StartQuery = std::chrono::steady_clock::now();
  401. #endif
  402. mpKeyFrameDB->DetectNBestCandidates(mpCurrentKF, vpLoopBowCand, vpMergeBowCand,3);
  403. #ifdef REGISTER_TIMES
  404. std::chrono::steady_clock::time_point time_EndQuery = std::chrono::steady_clock::now();
  405. double timeDataQuery = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndQuery - time_StartQuery).count();
  406. vdDataQuery_ms.push_back(timeDataQuery);
  407. #endif
  408. }
  409. #ifdef REGISTER_TIMES
  410. std::chrono::steady_clock::time_point time_StartEstSim3_2 = std::chrono::steady_clock::now();
  411. #endif
  412. // Check the BoW candidates if the geometric candidate list is empty
  413. //Loop candidates
  414. if(!bLoopDetectedInKF && !vpLoopBowCand.empty())
  415. {
  416. mbLoopDetected = DetectCommonRegionsFromBoW(vpLoopBowCand, mpLoopMatchedKF, mpLoopLastCurrentKF, mg2oLoopSlw, mnLoopNumCoincidences, mvpLoopMPs, mvpLoopMatchedMPs);
  417. }
  418. // Merge candidates
  419. if(!bMergeDetectedInKF && !vpMergeBowCand.empty())
  420. {
  421. mbMergeDetected = DetectCommonRegionsFromBoW(vpMergeBowCand, mpMergeMatchedKF, mpMergeLastCurrentKF, mg2oMergeSlw, mnMergeNumCoincidences, mvpMergeMPs, mvpMergeMatchedMPs);
  422. }
  423. #ifdef REGISTER_TIMES
  424. std::chrono::steady_clock::time_point time_EndEstSim3_2 = std::chrono::steady_clock::now();
  425. timeEstSim3 += std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndEstSim3_2 - time_StartEstSim3_2).count();
  426. vdEstSim3_ms.push_back(timeEstSim3);
  427. #endif
  428. mpKeyFrameDB->add(mpCurrentKF);
  429. if(mbMergeDetected || mbLoopDetected)
  430. {
  431. return true;
  432. }
  433. mpCurrentKF->SetErase();
  434. mpCurrentKF->mbCurrentPlaceRecognition = false;
  435. return false;
  436. }
  437. bool LoopClosing::DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  438. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
  439. {
  440. set<MapPoint*> spAlreadyMatchedMPs;
  441. nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
  442. int nProjMatches = 30;
  443. int nProjOptMatches = 50;
  444. int nProjMatchesRep = 100;
  445. if(nNumProjMatches >= nProjMatches)
  446. {
  447. //Verbose::PrintMess("Sim3 reffine: There are " + to_string(nNumProjMatches) + " initial matches ", Verbose::VERBOSITY_DEBUG);
  448. Sophus::SE3d mTwm = pMatchedKF->GetPoseInverse().cast<double>();
  449. g2o::Sim3 gSwm(mTwm.unit_quaternion(),mTwm.translation(),1.0);
  450. g2o::Sim3 gScm = gScw * gSwm;
  451. Eigen::Matrix<double, 7, 7> mHessian7x7;
  452. bool bFixedScale = mbFixScale; // TODO CHECK; Solo para el monocular inertial
  453. if(mpTracker->mSensor==System::IMU_MONOCULAR && !pCurrentKF->GetMap()->GetIniertialBA2())
  454. bFixedScale=false;
  455. int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pMatchedKF, vpMatchedMPs, gScm, 10, bFixedScale, mHessian7x7, true);
  456. //Verbose::PrintMess("Sim3 reffine: There are " + to_string(numOptMatches) + " matches after of the optimization ", Verbose::VERBOSITY_DEBUG);
  457. if(numOptMatches > nProjOptMatches)
  458. {
  459. g2o::Sim3 gScw_estimation(gScw.rotation(), gScw.translation(),1.0);
  460. vector<MapPoint*> vpMatchedMP;
  461. vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
  462. nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw_estimation, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
  463. if(nNumProjMatches >= nProjMatchesRep)
  464. {
  465. gScw = gScw_estimation;
  466. return true;
  467. }
  468. }
  469. }
  470. return false;
  471. }
  472. bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand, KeyFrame* &pMatchedKF2, KeyFrame* &pLastCurrentKF, g2o::Sim3 &g2oScw,
  473. int &nNumCoincidences, std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
  474. {
  475. int nBoWMatches = 20;
  476. int nBoWInliers = 15;
  477. int nSim3Inliers = 20;
  478. int nProjMatches = 50;
  479. int nProjOptMatches = 80;
  480. set<KeyFrame*> spConnectedKeyFrames = mpCurrentKF->GetConnectedKeyFrames();
  481. int nNumCovisibles = 10;
  482. ORBmatcher matcherBoW(0.9, true);
  483. ORBmatcher matcher(0.75, true);
  484. // Varibles to select the best numbe
  485. KeyFrame* pBestMatchedKF;
  486. int nBestMatchesReproj = 0;
  487. int nBestNumCoindicendes = 0;
  488. g2o::Sim3 g2oBestScw;
  489. std::vector<MapPoint*> vpBestMapPoints;
  490. std::vector<MapPoint*> vpBestMatchedMapPoints;
  491. int numCandidates = vpBowCand.size();
  492. vector<int> vnStage(numCandidates, 0);
  493. vector<int> vnMatchesStage(numCandidates, 0);
  494. int index = 0;
  495. //Verbose::PrintMess("BoW candidates: There are " + to_string(vpBowCand.size()) + " possible candidates ", Verbose::VERBOSITY_DEBUG);
  496. for(KeyFrame* pKFi : vpBowCand)
  497. {
  498. if(!pKFi || pKFi->isBad())
  499. continue;
  500. // std::cout << "KF candidate: " << pKFi->mnId << std::endl;
  501. // Current KF against KF with covisibles version
  502. std::vector<KeyFrame*> vpCovKFi = pKFi->GetBestCovisibilityKeyFrames(nNumCovisibles);
  503. if(vpCovKFi.empty())
  504. {
  505. std::cout << "Covisible list empty" << std::endl;
  506. vpCovKFi.push_back(pKFi);
  507. }
  508. else
  509. {
  510. vpCovKFi.push_back(vpCovKFi[0]);
  511. vpCovKFi[0] = pKFi;
  512. }
  513. bool bAbortByNearKF = false;
  514. for(int j=0; j<vpCovKFi.size(); ++j)
  515. {
  516. if(spConnectedKeyFrames.find(vpCovKFi[j]) != spConnectedKeyFrames.end())
  517. {
  518. bAbortByNearKF = true;
  519. break;
  520. }
  521. }
  522. if(bAbortByNearKF)
  523. {
  524. //std::cout << "Check BoW aborted because is close to the matched one " << std::endl;
  525. continue;
  526. }
  527. //std::cout << "Check BoW continue because is far to the matched one " << std::endl;
  528. std::vector<std::vector<MapPoint*> > vvpMatchedMPs;
  529. vvpMatchedMPs.resize(vpCovKFi.size());
  530. std::set<MapPoint*> spMatchedMPi;
  531. int numBoWMatches = 0;
  532. KeyFrame* pMostBoWMatchesKF = pKFi;
  533. int nMostBoWNumMatches = 0;
  534. std::vector<MapPoint*> vpMatchedPoints = std::vector<MapPoint*>(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
  535. std::vector<KeyFrame*> vpKeyFrameMatchedMP = std::vector<KeyFrame*>(mpCurrentKF->GetMapPointMatches().size(), static_cast<KeyFrame*>(NULL));
  536. int nIndexMostBoWMatchesKF=0;
  537. for(int j=0; j<vpCovKFi.size(); ++j)
  538. {
  539. if(!vpCovKFi[j] || vpCovKFi[j]->isBad())
  540. continue;
  541. int num = matcherBoW.SearchByBoW(mpCurrentKF, vpCovKFi[j], vvpMatchedMPs[j]);
  542. if (num > nMostBoWNumMatches)
  543. {
  544. nMostBoWNumMatches = num;
  545. nIndexMostBoWMatchesKF = j;
  546. }
  547. }
  548. for(int j=0; j<vpCovKFi.size(); ++j)
  549. {
  550. for(int k=0; k < vvpMatchedMPs[j].size(); ++k)
  551. {
  552. MapPoint* pMPi_j = vvpMatchedMPs[j][k];
  553. if(!pMPi_j || pMPi_j->isBad())
  554. continue;
  555. if(spMatchedMPi.find(pMPi_j) == spMatchedMPi.end())
  556. {
  557. spMatchedMPi.insert(pMPi_j);
  558. numBoWMatches++;
  559. vpMatchedPoints[k]= pMPi_j;
  560. vpKeyFrameMatchedMP[k] = vpCovKFi[j];
  561. }
  562. }
  563. }
  564. //pMostBoWMatchesKF = vpCovKFi[pMostBoWMatchesKF];
  565. if(numBoWMatches >= nBoWMatches) // TODO pick a good threshold
  566. {
  567. // Geometric validation
  568. bool bFixedScale = mbFixScale;
  569. if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
  570. bFixedScale=false;
  571. Sim3Solver solver = Sim3Solver(mpCurrentKF, pMostBoWMatchesKF, vpMatchedPoints, bFixedScale, vpKeyFrameMatchedMP);
  572. solver.SetRansacParameters(0.99, nBoWInliers, 300); // at least 15 inliers
  573. bool bNoMore = false;
  574. vector<bool> vbInliers;
  575. int nInliers;
  576. bool bConverge = false;
  577. Eigen::Matrix4f mTcm;
  578. while(!bConverge && !bNoMore)
  579. {
  580. mTcm = solver.iterate(20,bNoMore, vbInliers, nInliers, bConverge);
  581. //Verbose::PrintMess("BoW guess: Solver achieve " + to_string(nInliers) + " geometrical inliers among " + to_string(nBoWInliers) + " BoW matches", Verbose::VERBOSITY_DEBUG);
  582. }
  583. if(bConverge)
  584. {
  585. //std::cout << "Check BoW: SolverSim3 converged" << std::endl;
  586. //Verbose::PrintMess("BoW guess: Convergende with " + to_string(nInliers) + " geometrical inliers among " + to_string(nBoWInliers) + " BoW matches", Verbose::VERBOSITY_DEBUG);
  587. // Match by reprojection
  588. vpCovKFi.clear();
  589. vpCovKFi = pMostBoWMatchesKF->GetBestCovisibilityKeyFrames(nNumCovisibles);
  590. vpCovKFi.push_back(pMostBoWMatchesKF);
  591. set<KeyFrame*> spCheckKFs(vpCovKFi.begin(), vpCovKFi.end());
  592. //std::cout << "There are " << vpCovKFi.size() <<" near KFs" << std::endl;
  593. set<MapPoint*> spMapPoints;
  594. vector<MapPoint*> vpMapPoints;
  595. vector<KeyFrame*> vpKeyFrames;
  596. for(KeyFrame* pCovKFi : vpCovKFi)
  597. {
  598. for(MapPoint* pCovMPij : pCovKFi->GetMapPointMatches())
  599. {
  600. if(!pCovMPij || pCovMPij->isBad())
  601. continue;
  602. if(spMapPoints.find(pCovMPij) == spMapPoints.end())
  603. {
  604. spMapPoints.insert(pCovMPij);
  605. vpMapPoints.push_back(pCovMPij);
  606. vpKeyFrames.push_back(pCovKFi);
  607. }
  608. }
  609. }
  610. //std::cout << "There are " << vpKeyFrames.size() <<" KFs which view all the mappoints" << std::endl;
  611. g2o::Sim3 gScm(solver.GetEstimatedRotation().cast<double>(),solver.GetEstimatedTranslation().cast<double>(), (double) solver.GetEstimatedScale());
  612. g2o::Sim3 gSmw(pMostBoWMatchesKF->GetRotation().cast<double>(),pMostBoWMatchesKF->GetTranslation().cast<double>(),1.0);
  613. g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position
  614. Sophus::Sim3f mScw = Converter::toSophus(gScw);
  615. vector<MapPoint*> vpMatchedMP;
  616. vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
  617. vector<KeyFrame*> vpMatchedKF;
  618. vpMatchedKF.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<KeyFrame*>(NULL));
  619. int numProjMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpKeyFrames, vpMatchedMP, vpMatchedKF, 8, 1.5);
  620. //cout <<"BoW: " << numProjMatches << " matches between " << vpMapPoints.size() << " points with coarse Sim3" << endl;
  621. if(numProjMatches >= nProjMatches)
  622. {
  623. // Optimize Sim3 transformation with every matches
  624. Eigen::Matrix<double, 7, 7> mHessian7x7;
  625. bool bFixedScale = mbFixScale;
  626. if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
  627. bFixedScale=false;
  628. int numOptMatches = Optimizer::OptimizeSim3(mpCurrentKF, pKFi, vpMatchedMP, gScm, 10, mbFixScale, mHessian7x7, true);
  629. if(numOptMatches >= nSim3Inliers)
  630. {
  631. g2o::Sim3 gSmw(pMostBoWMatchesKF->GetRotation().cast<double>(),pMostBoWMatchesKF->GetTranslation().cast<double>(),1.0);
  632. g2o::Sim3 gScw = gScm*gSmw; // Similarity matrix of current from the world position
  633. Sophus::Sim3f mScw = Converter::toSophus(gScw);
  634. vector<MapPoint*> vpMatchedMP;
  635. vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
  636. int numProjOptMatches = matcher.SearchByProjection(mpCurrentKF, mScw, vpMapPoints, vpMatchedMP, 5, 1.0);
  637. if(numProjOptMatches >= nProjOptMatches)
  638. {
  639. int max_x = -1, min_x = 1000000;
  640. int max_y = -1, min_y = 1000000;
  641. for(MapPoint* pMPi : vpMatchedMP)
  642. {
  643. if(!pMPi || pMPi->isBad())
  644. {
  645. continue;
  646. }
  647. tuple<size_t,size_t> indexes = pMPi->GetIndexInKeyFrame(pKFi);
  648. int index = get<0>(indexes);
  649. if(index >= 0)
  650. {
  651. int coord_x = pKFi->mvKeysUn[index].pt.x;
  652. if(coord_x < min_x)
  653. {
  654. min_x = coord_x;
  655. }
  656. if(coord_x > max_x)
  657. {
  658. max_x = coord_x;
  659. }
  660. int coord_y = pKFi->mvKeysUn[index].pt.y;
  661. if(coord_y < min_y)
  662. {
  663. min_y = coord_y;
  664. }
  665. if(coord_y > max_y)
  666. {
  667. max_y = coord_y;
  668. }
  669. }
  670. }
  671. int nNumKFs = 0;
  672. //vpMatchedMPs = vpMatchedMP;
  673. //vpMPs = vpMapPoints;
  674. // Check the Sim3 transformation with the current KeyFrame covisibles
  675. vector<KeyFrame*> vpCurrentCovKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(nNumCovisibles);
  676. int j = 0;
  677. while(nNumKFs < 3 && j<vpCurrentCovKFs.size())
  678. {
  679. KeyFrame* pKFj = vpCurrentCovKFs[j];
  680. Sophus::SE3d mTjc = (pKFj->GetPose() * mpCurrentKF->GetPoseInverse()).cast<double>();
  681. g2o::Sim3 gSjc(mTjc.unit_quaternion(),mTjc.translation(),1.0);
  682. g2o::Sim3 gSjw = gSjc * gScw;
  683. int numProjMatches_j = 0;
  684. vector<MapPoint*> vpMatchedMPs_j;
  685. bool bValid = DetectCommonRegionsFromLastKF(pKFj,pMostBoWMatchesKF, gSjw,numProjMatches_j, vpMapPoints, vpMatchedMPs_j);
  686. if(bValid)
  687. {
  688. Sophus::SE3f Tc_w = mpCurrentKF->GetPose();
  689. Sophus::SE3f Tw_cj = pKFj->GetPoseInverse();
  690. Sophus::SE3f Tc_cj = Tc_w * Tw_cj;
  691. Eigen::Vector3f vector_dist = Tc_cj.translation();
  692. nNumKFs++;
  693. }
  694. j++;
  695. }
  696. if(nNumKFs < 3)
  697. {
  698. vnStage[index] = 8;
  699. vnMatchesStage[index] = nNumKFs;
  700. }
  701. if(nBestMatchesReproj < numProjOptMatches)
  702. {
  703. nBestMatchesReproj = numProjOptMatches;
  704. nBestNumCoindicendes = nNumKFs;
  705. pBestMatchedKF = pMostBoWMatchesKF;
  706. g2oBestScw = gScw;
  707. vpBestMapPoints = vpMapPoints;
  708. vpBestMatchedMapPoints = vpMatchedMP;
  709. }
  710. }
  711. }
  712. }
  713. }
  714. /*else
  715. {
  716. Verbose::PrintMess("BoW candidate: it don't match with the current one", Verbose::VERBOSITY_DEBUG);
  717. }*/
  718. }
  719. index++;
  720. }
  721. if(nBestMatchesReproj > 0)
  722. {
  723. pLastCurrentKF = mpCurrentKF;
  724. nNumCoincidences = nBestNumCoindicendes;
  725. pMatchedKF2 = pBestMatchedKF;
  726. pMatchedKF2->SetNotErase();
  727. g2oScw = g2oBestScw;
  728. vpMPs = vpBestMapPoints;
  729. vpMatchedMPs = vpBestMatchedMapPoints;
  730. return nNumCoincidences >= 3;
  731. }
  732. else
  733. {
  734. int maxStage = -1;
  735. int maxMatched;
  736. for(int i=0; i<vnStage.size(); ++i)
  737. {
  738. if(vnStage[i] > maxStage)
  739. {
  740. maxStage = vnStage[i];
  741. maxMatched = vnMatchesStage[i];
  742. }
  743. }
  744. }
  745. return false;
  746. }
  747. bool LoopClosing::DetectCommonRegionsFromLastKF(KeyFrame* pCurrentKF, KeyFrame* pMatchedKF, g2o::Sim3 &gScw, int &nNumProjMatches,
  748. std::vector<MapPoint*> &vpMPs, std::vector<MapPoint*> &vpMatchedMPs)
  749. {
  750. set<MapPoint*> spAlreadyMatchedMPs(vpMatchedMPs.begin(), vpMatchedMPs.end());
  751. nNumProjMatches = FindMatchesByProjection(pCurrentKF, pMatchedKF, gScw, spAlreadyMatchedMPs, vpMPs, vpMatchedMPs);
  752. int nProjMatches = 30;
  753. if(nNumProjMatches >= nProjMatches)
  754. {
  755. return true;
  756. }
  757. return false;
  758. }
  759. int LoopClosing::FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatchedKFw, g2o::Sim3 &g2oScw,
  760. set<MapPoint*> &spMatchedMPinOrigin, vector<MapPoint*> &vpMapPoints,
  761. vector<MapPoint*> &vpMatchedMapPoints)
  762. {
  763. int nNumCovisibles = 10;
  764. vector<KeyFrame*> vpCovKFm = pMatchedKFw->GetBestCovisibilityKeyFrames(nNumCovisibles);
  765. int nInitialCov = vpCovKFm.size();
  766. vpCovKFm.push_back(pMatchedKFw);
  767. set<KeyFrame*> spCheckKFs(vpCovKFm.begin(), vpCovKFm.end());
  768. set<KeyFrame*> spCurrentCovisbles = pCurrentKF->GetConnectedKeyFrames();
  769. if(nInitialCov < nNumCovisibles)
  770. {
  771. for(int i=0; i<nInitialCov; ++i)
  772. {
  773. vector<KeyFrame*> vpKFs = vpCovKFm[i]->GetBestCovisibilityKeyFrames(nNumCovisibles);
  774. int nInserted = 0;
  775. int j = 0;
  776. while(j < vpKFs.size() && nInserted < nNumCovisibles)
  777. {
  778. if(spCheckKFs.find(vpKFs[j]) == spCheckKFs.end() && spCurrentCovisbles.find(vpKFs[j]) == spCurrentCovisbles.end())
  779. {
  780. spCheckKFs.insert(vpKFs[j]);
  781. ++nInserted;
  782. }
  783. ++j;
  784. }
  785. vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end());
  786. }
  787. }
  788. set<MapPoint*> spMapPoints;
  789. vpMapPoints.clear();
  790. vpMatchedMapPoints.clear();
  791. for(KeyFrame* pKFi : vpCovKFm)
  792. {
  793. for(MapPoint* pMPij : pKFi->GetMapPointMatches())
  794. {
  795. if(!pMPij || pMPij->isBad())
  796. continue;
  797. if(spMapPoints.find(pMPij) == spMapPoints.end())
  798. {
  799. spMapPoints.insert(pMPij);
  800. vpMapPoints.push_back(pMPij);
  801. }
  802. }
  803. }
  804. Sophus::Sim3f mScw = Converter::toSophus(g2oScw);
  805. ORBmatcher matcher(0.9, true);
  806. vpMatchedMapPoints.resize(pCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
  807. int num_matches = matcher.SearchByProjection(pCurrentKF, mScw, vpMapPoints, vpMatchedMapPoints, 3, 1.5);
  808. return num_matches;
  809. }
  810. void LoopClosing::CorrectLoop()
  811. {
  812. //cout << "Loop detected!" << endl;
  813. // Send a stop signal to Local Mapping
  814. // Avoid new keyframes are inserted while correcting the loop
  815. mpLocalMapper->RequestStop();
  816. mpLocalMapper->EmptyQueue(); // Proccess keyframes in the queue
  817. // If a Global Bundle Adjustment is running, abort it
  818. if(isRunningGBA())
  819. {
  820. cout << "Stoping Global Bundle Adjustment...";
  821. unique_lock<mutex> lock(mMutexGBA);
  822. mbStopGBA = true;
  823. mnFullBAIdx++;
  824. if(mpThreadGBA)
  825. {
  826. mpThreadGBA->detach();
  827. delete mpThreadGBA;
  828. }
  829. cout << " Done!!" << endl;
  830. }
  831. // Wait until Local Mapping has effectively stopped
  832. while(!mpLocalMapper->isStopped())
  833. {
  834. usleep(1000);
  835. }
  836. // Ensure current keyframe is updated
  837. //cout << "Start updating connections" << endl;
  838. //assert(mpCurrentKF->GetMap()->CheckEssentialGraph());
  839. mpCurrentKF->UpdateConnections();
  840. //assert(mpCurrentKF->GetMap()->CheckEssentialGraph());
  841. // Retrive keyframes connected to the current keyframe and compute corrected Sim3 pose by propagation
  842. mvpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames();
  843. mvpCurrentConnectedKFs.push_back(mpCurrentKF);
  844. //std::cout << "Loop: number of connected KFs -> " + to_string(mvpCurrentConnectedKFs.size()) << std::endl;
  845. KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
  846. CorrectedSim3[mpCurrentKF]=mg2oLoopScw;
  847. Sophus::SE3f Twc = mpCurrentKF->GetPoseInverse();
  848. Sophus::SE3f Tcw = mpCurrentKF->GetPose();
  849. g2o::Sim3 g2oScw(Tcw.unit_quaternion().cast<double>(),Tcw.translation().cast<double>(),1.0);
  850. NonCorrectedSim3[mpCurrentKF]=g2oScw;
  851. // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
  852. Sophus::SE3d correctedTcw(mg2oLoopScw.rotation(),mg2oLoopScw.translation() / mg2oLoopScw.scale());
  853. mpCurrentKF->SetPose(correctedTcw.cast<float>());
  854. Map* pLoopMap = mpCurrentKF->GetMap();
  855. #ifdef REGISTER_TIMES
  856. /*KeyFrame* pKF = mpCurrentKF;
  857. int numKFinLoop = 0;
  858. while(pKF && pKF->mnId > mpLoopMatchedKF->mnId)
  859. {
  860. pKF = pKF->GetParent();
  861. numKFinLoop += 1;
  862. }
  863. vnLoopKFs.push_back(numKFinLoop);*/
  864. std::chrono::steady_clock::time_point time_StartFusion = std::chrono::steady_clock::now();
  865. #endif
  866. {
  867. // Get Map Mutex
  868. unique_lock<mutex> lock(pLoopMap->mMutexMapUpdate);
  869. const bool bImuInit = pLoopMap->isImuInitialized();
  870. for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
  871. {
  872. KeyFrame* pKFi = *vit;
  873. if(pKFi!=mpCurrentKF)
  874. {
  875. Sophus::SE3f Tiw = pKFi->GetPose();
  876. Sophus::SE3d Tic = (Tiw * Twc).cast<double>();
  877. g2o::Sim3 g2oSic(Tic.unit_quaternion(),Tic.translation(),1.0);
  878. g2o::Sim3 g2oCorrectedSiw = g2oSic*mg2oLoopScw;
  879. //Pose corrected with the Sim3 of the loop closure
  880. CorrectedSim3[pKFi]=g2oCorrectedSiw;
  881. // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
  882. Sophus::SE3d correctedTiw(g2oCorrectedSiw.rotation(),g2oCorrectedSiw.translation() / g2oCorrectedSiw.scale());
  883. pKFi->SetPose(correctedTiw.cast<float>());
  884. //Pose without correction
  885. g2o::Sim3 g2oSiw(Tiw.unit_quaternion().cast<double>(),Tiw.translation().cast<double>(),1.0);
  886. NonCorrectedSim3[pKFi]=g2oSiw;
  887. }
  888. }
  889. // Correct all MapPoints obsrved by current keyframe and neighbors, so that they align with the other side of the loop
  890. for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
  891. {
  892. KeyFrame* pKFi = mit->first;
  893. g2o::Sim3 g2oCorrectedSiw = mit->second;
  894. g2o::Sim3 g2oCorrectedSwi = g2oCorrectedSiw.inverse();
  895. g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi];
  896. // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
  897. /*Sophus::SE3d correctedTiw(g2oCorrectedSiw.rotation(),g2oCorrectedSiw.translation() / g2oCorrectedSiw.scale());
  898. pKFi->SetPose(correctedTiw.cast<float>());*/
  899. vector<MapPoint*> vpMPsi = pKFi->GetMapPointMatches();
  900. for(size_t iMP=0, endMPi = vpMPsi.size(); iMP<endMPi; iMP++)
  901. {
  902. MapPoint* pMPi = vpMPsi[iMP];
  903. if(!pMPi)
  904. continue;
  905. if(pMPi->isBad())
  906. continue;
  907. if(pMPi->mnCorrectedByKF==mpCurrentKF->mnId)
  908. continue;
  909. // Project with non-corrected pose and project back with corrected pose
  910. Eigen::Vector3d P3Dw = pMPi->GetWorldPos().cast<double>();
  911. Eigen::Vector3d eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oSiw.map(P3Dw));
  912. pMPi->SetWorldPos(eigCorrectedP3Dw.cast<float>());
  913. pMPi->mnCorrectedByKF = mpCurrentKF->mnId;
  914. pMPi->mnCorrectedReference = pKFi->mnId;
  915. pMPi->UpdateNormalAndDepth();
  916. }
  917. // Correct velocity according to orientation correction
  918. if(bImuInit)
  919. {
  920. Eigen::Quaternionf Rcor = (g2oCorrectedSiw.rotation().inverse()*g2oSiw.rotation()).cast<float>();
  921. pKFi->SetVelocity(Rcor*pKFi->GetVelocity());
  922. }
  923. // Make sure connections are updated
  924. pKFi->UpdateConnections();
  925. }
  926. // TODO Check this index increasement
  927. mpAtlas->GetCurrentMap()->IncreaseChangeIndex();
  928. // Start Loop Fusion
  929. // Update matched map points and replace if duplicated
  930. for(size_t i=0; i<mvpLoopMatchedMPs.size(); i++)
  931. {
  932. if(mvpLoopMatchedMPs[i])
  933. {
  934. MapPoint* pLoopMP = mvpLoopMatchedMPs[i];
  935. MapPoint* pCurMP = mpCurrentKF->GetMapPoint(i);
  936. if(pCurMP)
  937. pCurMP->Replace(pLoopMP);
  938. else
  939. {
  940. mpCurrentKF->AddMapPoint(pLoopMP,i);
  941. pLoopMP->AddObservation(mpCurrentKF,i);
  942. pLoopMP->ComputeDistinctiveDescriptors();
  943. }
  944. }
  945. }
  946. //cout << "LC: end replacing duplicated" << endl;
  947. }
  948. // Project MapPoints observed in the neighborhood of the loop keyframe
  949. // into the current keyframe and neighbors using corrected poses.
  950. // Fuse duplications.
  951. SearchAndFuse(CorrectedSim3, mvpLoopMapPoints);
  952. // After the MapPoint fusion, new links in the covisibility graph will appear attaching both sides of the loop
  953. map<KeyFrame*, set<KeyFrame*> > LoopConnections;
  954. for(vector<KeyFrame*>::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++)
  955. {
  956. KeyFrame* pKFi = *vit;
  957. vector<KeyFrame*> vpPreviousNeighbors = pKFi->GetVectorCovisibleKeyFrames();
  958. // Update connections. Detect new links.
  959. pKFi->UpdateConnections();
  960. LoopConnections[pKFi]=pKFi->GetConnectedKeyFrames();
  961. for(vector<KeyFrame*>::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++)
  962. {
  963. LoopConnections[pKFi].erase(*vit_prev);
  964. }
  965. for(vector<KeyFrame*>::iterator vit2=mvpCurrentConnectedKFs.begin(), vend2=mvpCurrentConnectedKFs.end(); vit2!=vend2; vit2++)
  966. {
  967. LoopConnections[pKFi].erase(*vit2);
  968. }
  969. }
  970. // Optimize graph
  971. bool bFixedScale = mbFixScale;
  972. // TODO CHECK; Solo para el monocular inertial
  973. if(mpTracker->mSensor==System::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
  974. bFixedScale=false;
  975. #ifdef REGISTER_TIMES
  976. std::chrono::steady_clock::time_point time_EndFusion = std::chrono::steady_clock::now();
  977. double timeFusion = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndFusion - time_StartFusion).count();
  978. vdLoopFusion_ms.push_back(timeFusion);
  979. #endif
  980. //cout << "Optimize essential graph" << endl;
  981. if(pLoopMap->IsInertial() && pLoopMap->isImuInitialized())
  982. {
  983. Optimizer::OptimizeEssentialGraph4DoF(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections);
  984. }
  985. else
  986. {
  987. //cout << "Loop -> Scale correction: " << mg2oLoopScw.scale() << endl;
  988. Optimizer::OptimizeEssentialGraph(pLoopMap, mpLoopMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, bFixedScale);
  989. }
  990. #ifdef REGISTER_TIMES
  991. std::chrono::steady_clock::time_point time_EndOpt = std::chrono::steady_clock::now();
  992. double timeOptEss = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndOpt - time_EndFusion).count();
  993. vdLoopOptEss_ms.push_back(timeOptEss);
  994. #endif
  995. mpAtlas->InformNewBigChange();
  996. // Add loop edge
  997. mpLoopMatchedKF->AddLoopEdge(mpCurrentKF);
  998. mpCurrentKF->AddLoopEdge(mpLoopMatchedKF);
  999. // Launch a new thread to perform Global Bundle Adjustment (Only if few keyframes, if not it would take too much time)
  1000. if(!pLoopMap->isImuInitialized() || (pLoopMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1))
  1001. {
  1002. mbRunningGBA = true;
  1003. mbFinishedGBA = false;
  1004. mbStopGBA = false;
  1005. mnCorrectionGBA = mnNumCorrection;
  1006. mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment, this, pLoopMap, mpCurrentKF->mnId);
  1007. }
  1008. // Loop closed. Release Local Mapping.
  1009. mpLocalMapper->Release();
  1010. mLastLoopKFid = mpCurrentKF->mnId; //TODO old varible, it is not use in the new algorithm
  1011. }
  1012. void LoopClosing::MergeLocal()
  1013. {
  1014. int numTemporalKFs = 25; //Temporal KFs in the local window if the map is inertial.
  1015. //Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map
  1016. KeyFrame* pNewChild;
  1017. KeyFrame* pNewParent;
  1018. vector<KeyFrame*> vpLocalCurrentWindowKFs;
  1019. vector<KeyFrame*> vpMergeConnectedKFs;
  1020. // Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge
  1021. bool bRelaunchBA = false;
  1022. //Verbose::PrintMess("MERGE-VISUAL: Check Full Bundle Adjustment", Verbose::VERBOSITY_DEBUG);
  1023. // If a Global Bundle Adjustment is running, abort it
  1024. if(isRunningGBA())
  1025. {
  1026. unique_lock<mutex> lock(mMutexGBA);
  1027. mbStopGBA = true;
  1028. mnFullBAIdx++;
  1029. if(mpThreadGBA)
  1030. {
  1031. mpThreadGBA->detach();
  1032. delete mpThreadGBA;
  1033. }
  1034. bRelaunchBA = true;
  1035. }
  1036. //Verbose::PrintMess("MERGE-VISUAL: Request Stop Local Mapping", Verbose::VERBOSITY_DEBUG);
  1037. //cout << "Request Stop Local Mapping" << endl;
  1038. mpLocalMapper->RequestStop();
  1039. // Wait until Local Mapping has effectively stopped
  1040. while(!mpLocalMapper->isStopped())
  1041. {
  1042. usleep(1000);
  1043. }
  1044. //cout << "Local Map stopped" << endl;
  1045. mpLocalMapper->EmptyQueue();
  1046. // Merge map will become in the new active map with the local window of KFs and MPs from the current map.
  1047. // Later, the elements of the current map will be transform to the new active map reference, in order to keep real time tracking
  1048. Map* pCurrentMap = mpCurrentKF->GetMap();
  1049. Map* pMergeMap = mpMergeMatchedKF->GetMap();
  1050. //std::cout << "Merge local, Active map: " << pCurrentMap->GetId() << std::endl;
  1051. //std::cout << "Merge local, Non-Active map: " << pMergeMap->GetId() << std::endl;
  1052. #ifdef REGISTER_TIMES
  1053. std::chrono::steady_clock::time_point time_StartMerge = std::chrono::steady_clock::now();
  1054. #endif
  1055. // Ensure current keyframe is updated
  1056. mpCurrentKF->UpdateConnections();
  1057. //Get the current KF and its neighbors(visual->covisibles; inertial->temporal+covisibles)
  1058. set<KeyFrame*> spLocalWindowKFs;
  1059. //Get MPs in the welding area from the current map
  1060. set<MapPoint*> spLocalWindowMPs;
  1061. if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization
  1062. {
  1063. KeyFrame* pKFi = mpCurrentKF;
  1064. int nInserted = 0;
  1065. while(pKFi && nInserted < numTemporalKFs)
  1066. {
  1067. spLocalWindowKFs.insert(pKFi);
  1068. pKFi = mpCurrentKF->mPrevKF;
  1069. nInserted++;
  1070. set<MapPoint*> spMPi = pKFi->GetMapPoints();
  1071. spLocalWindowMPs.insert(spMPi.begin(), spMPi.end());
  1072. }
  1073. pKFi = mpCurrentKF->mNextKF;
  1074. while(pKFi)
  1075. {
  1076. spLocalWindowKFs.insert(pKFi);
  1077. set<MapPoint*> spMPi = pKFi->GetMapPoints();
  1078. spLocalWindowMPs.insert(spMPi.begin(), spMPi.end());
  1079. pKFi = mpCurrentKF->mNextKF;
  1080. }
  1081. }
  1082. else
  1083. {
  1084. spLocalWindowKFs.insert(mpCurrentKF);
  1085. }
  1086. vector<KeyFrame*> vpCovisibleKFs = mpCurrentKF->GetBestCovisibilityKeyFrames(numTemporalKFs);
  1087. spLocalWindowKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end());
  1088. spLocalWindowKFs.insert(mpCurrentKF);
  1089. const int nMaxTries = 5;
  1090. int nNumTries = 0;
  1091. while(spLocalWindowKFs.size() < numTemporalKFs && nNumTries < nMaxTries)
  1092. {
  1093. vector<KeyFrame*> vpNewCovKFs;
  1094. vpNewCovKFs.empty();
  1095. for(KeyFrame* pKFi : spLocalWindowKFs)
  1096. {
  1097. vector<KeyFrame*> vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2);
  1098. for(KeyFrame* pKFcov : vpKFiCov)
  1099. {
  1100. if(pKFcov && !pKFcov->isBad() && spLocalWindowKFs.find(pKFcov) == spLocalWindowKFs.end())
  1101. {
  1102. vpNewCovKFs.push_back(pKFcov);
  1103. }
  1104. }
  1105. }
  1106. spLocalWindowKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end());
  1107. nNumTries++;
  1108. }
  1109. for(KeyFrame* pKFi : spLocalWindowKFs)
  1110. {
  1111. if(!pKFi || pKFi->isBad())
  1112. continue;
  1113. set<MapPoint*> spMPs = pKFi->GetMapPoints();
  1114. spLocalWindowMPs.insert(spMPs.begin(), spMPs.end());
  1115. }
  1116. //std::cout << "[Merge]: Ma = " << to_string(pCurrentMap->GetId()) << "; #KFs = " << to_string(spLocalWindowKFs.size()) << "; #MPs = " << to_string(spLocalWindowMPs.size()) << std::endl;
  1117. set<KeyFrame*> spMergeConnectedKFs;
  1118. if(pCurrentMap->IsInertial() && pMergeMap->IsInertial()) //TODO Check the correct initialization
  1119. {
  1120. KeyFrame* pKFi = mpMergeMatchedKF;
  1121. int nInserted = 0;
  1122. while(pKFi && nInserted < numTemporalKFs/2)
  1123. {
  1124. spMergeConnectedKFs.insert(pKFi);
  1125. pKFi = mpCurrentKF->mPrevKF;
  1126. nInserted++;
  1127. }
  1128. pKFi = mpMergeMatchedKF->mNextKF;
  1129. while(pKFi && nInserted < numTemporalKFs)
  1130. {
  1131. spMergeConnectedKFs.insert(pKFi);
  1132. pKFi = mpCurrentKF->mNextKF;
  1133. }
  1134. }
  1135. else
  1136. {
  1137. spMergeConnectedKFs.insert(mpMergeMatchedKF);
  1138. }
  1139. vpCovisibleKFs = mpMergeMatchedKF->GetBestCovisibilityKeyFrames(numTemporalKFs);
  1140. spMergeConnectedKFs.insert(vpCovisibleKFs.begin(), vpCovisibleKFs.end());
  1141. spMergeConnectedKFs.insert(mpMergeMatchedKF);
  1142. nNumTries = 0;
  1143. while(spMergeConnectedKFs.size() < numTemporalKFs && nNumTries < nMaxTries)
  1144. {
  1145. vector<KeyFrame*> vpNewCovKFs;
  1146. for(KeyFrame* pKFi : spMergeConnectedKFs)
  1147. {
  1148. vector<KeyFrame*> vpKFiCov = pKFi->GetBestCovisibilityKeyFrames(numTemporalKFs/2);
  1149. for(KeyFrame* pKFcov : vpKFiCov)
  1150. {
  1151. if(pKFcov && !pKFcov->isBad() && spMergeConnectedKFs.find(pKFcov) == spMergeConnectedKFs.end())
  1152. {
  1153. vpNewCovKFs.push_back(pKFcov);
  1154. }
  1155. }
  1156. }
  1157. spMergeConnectedKFs.insert(vpNewCovKFs.begin(), vpNewCovKFs.end());
  1158. nNumTries++;
  1159. }
  1160. set<MapPoint*> spMapPointMerge;
  1161. for(KeyFrame* pKFi : spMergeConnectedKFs)
  1162. {
  1163. set<MapPoint*> vpMPs = pKFi->GetMapPoints();
  1164. spMapPointMerge.insert(vpMPs.begin(),vpMPs.end());
  1165. }
  1166. vector<MapPoint*> vpCheckFuseMapPoint;
  1167. vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
  1168. std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
  1169. //std::cout << "[Merge]: Mm = " << to_string(pMergeMap->GetId()) << "; #KFs = " << to_string(spMergeConnectedKFs.size()) << "; #MPs = " << to_string(spMapPointMerge.size()) << std::endl;
  1170. //
  1171. Sophus::SE3d Twc = mpCurrentKF->GetPoseInverse().cast<double>();
  1172. g2o::Sim3 g2oNonCorrectedSwc(Twc.unit_quaternion(),Twc.translation(),1.0);
  1173. g2o::Sim3 g2oNonCorrectedScw = g2oNonCorrectedSwc.inverse();
  1174. g2o::Sim3 g2oCorrectedScw = mg2oMergeScw; //TODO Check the transformation
  1175. KeyFrameAndPose vCorrectedSim3, vNonCorrectedSim3;
  1176. vCorrectedSim3[mpCurrentKF]=g2oCorrectedScw;
  1177. vNonCorrectedSim3[mpCurrentKF]=g2oNonCorrectedScw;
  1178. #ifdef REGISTER_TIMES
  1179. vnMergeKFs.push_back(spLocalWindowKFs.size() + spMergeConnectedKFs.size());
  1180. vnMergeMPs.push_back(spLocalWindowMPs.size() + spMapPointMerge.size());
  1181. #endif
  1182. for(KeyFrame* pKFi : spLocalWindowKFs)
  1183. {
  1184. if(!pKFi || pKFi->isBad())
  1185. {
  1186. Verbose::PrintMess("Bad KF in correction", Verbose::VERBOSITY_DEBUG);
  1187. continue;
  1188. }
  1189. if(pKFi->GetMap() != pCurrentMap)
  1190. Verbose::PrintMess("Other map KF, this should't happen", Verbose::VERBOSITY_DEBUG);
  1191. g2o::Sim3 g2oCorrectedSiw;
  1192. if(pKFi!=mpCurrentKF)
  1193. {
  1194. Sophus::SE3d Tiw = (pKFi->GetPose()).cast<double>();
  1195. g2o::Sim3 g2oSiw(Tiw.unit_quaternion(),Tiw.translation(),1.0);
  1196. //Pose without correction
  1197. vNonCorrectedSim3[pKFi]=g2oSiw;
  1198. Sophus::SE3d Tic = Tiw*Twc;
  1199. g2o::Sim3 g2oSic(Tic.unit_quaternion(),Tic.translation(),1.0);
  1200. g2oCorrectedSiw = g2oSic*mg2oMergeScw;
  1201. vCorrectedSim3[pKFi]=g2oCorrectedSiw;
  1202. }
  1203. else
  1204. {
  1205. g2oCorrectedSiw = g2oCorrectedScw;
  1206. }
  1207. pKFi->mTcwMerge = pKFi->GetPose();
  1208. // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
  1209. double s = g2oCorrectedSiw.scale();
  1210. pKFi->mfScale = s;
  1211. Sophus::SE3d correctedTiw(g2oCorrectedSiw.rotation(), g2oCorrectedSiw.translation() / s);
  1212. pKFi->mTcwMerge = correctedTiw.cast<float>();
  1213. if(pCurrentMap->isImuInitialized())
  1214. {
  1215. Eigen::Quaternionf Rcor = (g2oCorrectedSiw.rotation().inverse() * vNonCorrectedSim3[pKFi].rotation()).cast<float>();
  1216. pKFi->mVwbMerge = Rcor * pKFi->GetVelocity();
  1217. }
  1218. //TODO DEBUG to know which are the KFs that had been moved to the other map
  1219. }
  1220. int numPointsWithCorrection = 0;
  1221. //for(MapPoint* pMPi : spLocalWindowMPs)
  1222. set<MapPoint*>::iterator itMP = spLocalWindowMPs.begin();
  1223. while(itMP != spLocalWindowMPs.end())
  1224. {
  1225. MapPoint* pMPi = *itMP;
  1226. if(!pMPi || pMPi->isBad())
  1227. {
  1228. itMP = spLocalWindowMPs.erase(itMP);
  1229. continue;
  1230. }
  1231. KeyFrame* pKFref = pMPi->GetReferenceKeyFrame();
  1232. if(vCorrectedSim3.find(pKFref) == vCorrectedSim3.end())
  1233. {
  1234. itMP = spLocalWindowMPs.erase(itMP);
  1235. numPointsWithCorrection++;
  1236. continue;
  1237. }
  1238. g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse();
  1239. g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref];
  1240. // Project with non-corrected pose and project back with corrected pose
  1241. Eigen::Vector3d P3Dw = pMPi->GetWorldPos().cast<double>();
  1242. Eigen::Vector3d eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(P3Dw));
  1243. Eigen::Quaterniond Rcor = g2oCorrectedSwi.rotation() * g2oNonCorrectedSiw.rotation();
  1244. pMPi->mPosMerge = eigCorrectedP3Dw.cast<float>();
  1245. pMPi->mNormalVectorMerge = Rcor.cast<float>() * pMPi->GetNormal();
  1246. itMP++;
  1247. }
  1248. /*if(numPointsWithCorrection>0)
  1249. {
  1250. std::cout << "[Merge]: " << std::to_string(numPointsWithCorrection) << " points removed from Ma due to its reference KF is not in welding area" << std::endl;
  1251. std::cout << "[Merge]: Ma has " << std::to_string(spLocalWindowMPs.size()) << " points" << std::endl;
  1252. }*/
  1253. {
  1254. unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
  1255. unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
  1256. //std::cout << "Merge local window: " << spLocalWindowKFs.size() << std::endl;
  1257. //std::cout << "[Merge]: init merging maps " << std::endl;
  1258. for(KeyFrame* pKFi : spLocalWindowKFs)
  1259. {
  1260. if(!pKFi || pKFi->isBad())
  1261. {
  1262. //std::cout << "Bad KF in correction" << std::endl;
  1263. continue;
  1264. }
  1265. //std::cout << "KF id: " << pKFi->mnId << std::endl;
  1266. pKFi->mTcwBefMerge = pKFi->GetPose();
  1267. pKFi->mTwcBefMerge = pKFi->GetPoseInverse();
  1268. pKFi->SetPose(pKFi->mTcwMerge);
  1269. // Make sure connections are updated
  1270. pKFi->UpdateMap(pMergeMap);
  1271. pKFi->mnMergeCorrectedForKF = mpCurrentKF->mnId;
  1272. pMergeMap->AddKeyFrame(pKFi);
  1273. pCurrentMap->EraseKeyFrame(pKFi);
  1274. if(pCurrentMap->isImuInitialized())
  1275. {
  1276. pKFi->SetVelocity(pKFi->mVwbMerge);
  1277. }
  1278. }
  1279. for(MapPoint* pMPi : spLocalWindowMPs)
  1280. {
  1281. if(!pMPi || pMPi->isBad())
  1282. continue;
  1283. pMPi->SetWorldPos(pMPi->mPosMerge);
  1284. pMPi->SetNormalVector(pMPi->mNormalVectorMerge);
  1285. pMPi->UpdateMap(pMergeMap);
  1286. pMergeMap->AddMapPoint(pMPi);
  1287. pCurrentMap->EraseMapPoint(pMPi);
  1288. }
  1289. mpAtlas->ChangeMap(pMergeMap);
  1290. mpAtlas->SetMapBad(pCurrentMap);
  1291. pMergeMap->IncreaseChangeIndex();
  1292. //TODO for debug
  1293. pMergeMap->ChangeId(pCurrentMap->GetId());
  1294. //std::cout << "[Merge]: merging maps finished" << std::endl;
  1295. }
  1296. //Rebuild the essential graph in the local window
  1297. pCurrentMap->GetOriginKF()->SetFirstConnection(false);
  1298. pNewChild = mpCurrentKF->GetParent(); // Old parent, it will be the new child of this KF
  1299. pNewParent = mpCurrentKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent)
  1300. mpCurrentKF->ChangeParent(mpMergeMatchedKF);
  1301. while(pNewChild)
  1302. {
  1303. pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop
  1304. KeyFrame * pOldParent = pNewChild->GetParent();
  1305. pNewChild->ChangeParent(pNewParent);
  1306. pNewParent = pNewChild;
  1307. pNewChild = pOldParent;
  1308. }
  1309. //Update the connections between the local window
  1310. mpMergeMatchedKF->UpdateConnections();
  1311. vpMergeConnectedKFs = mpMergeMatchedKF->GetVectorCovisibleKeyFrames();
  1312. vpMergeConnectedKFs.push_back(mpMergeMatchedKF);
  1313. //vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
  1314. //std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
  1315. // Project MapPoints observed in the neighborhood of the merge keyframe
  1316. // into the current keyframe and neighbors using corrected poses.
  1317. // Fuse duplications.
  1318. //std::cout << "[Merge]: start fuse points" << std::endl;
  1319. SearchAndFuse(vCorrectedSim3, vpCheckFuseMapPoint);
  1320. //std::cout << "[Merge]: fuse points finished" << std::endl;
  1321. // Update connectivity
  1322. for(KeyFrame* pKFi : spLocalWindowKFs)
  1323. {
  1324. if(!pKFi || pKFi->isBad())
  1325. continue;
  1326. pKFi->UpdateConnections();
  1327. }
  1328. for(KeyFrame* pKFi : spMergeConnectedKFs)
  1329. {
  1330. if(!pKFi || pKFi->isBad())
  1331. continue;
  1332. pKFi->UpdateConnections();
  1333. }
  1334. //std::cout << "[Merge]: Start welding bundle adjustment" << std::endl;
  1335. #ifdef REGISTER_TIMES
  1336. std::chrono::steady_clock::time_point time_StartWeldingBA = std::chrono::steady_clock::now();
  1337. double timeMergeMaps = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_StartWeldingBA - time_StartMerge).count();
  1338. vdMergeMaps_ms.push_back(timeMergeMaps);
  1339. #endif
  1340. bool bStop = false;
  1341. vpLocalCurrentWindowKFs.clear();
  1342. vpMergeConnectedKFs.clear();
  1343. std::copy(spLocalWindowKFs.begin(), spLocalWindowKFs.end(), std::back_inserter(vpLocalCurrentWindowKFs));
  1344. std::copy(spMergeConnectedKFs.begin(), spMergeConnectedKFs.end(), std::back_inserter(vpMergeConnectedKFs));
  1345. if (mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD)
  1346. {
  1347. Optimizer::MergeInertialBA(mpCurrentKF,mpMergeMatchedKF,&bStop, pCurrentMap,vCorrectedSim3);
  1348. }
  1349. else
  1350. {
  1351. Optimizer::LocalBundleAdjustment(mpCurrentKF, vpLocalCurrentWindowKFs, vpMergeConnectedKFs,&bStop);
  1352. }
  1353. #ifdef REGISTER_TIMES
  1354. std::chrono::steady_clock::time_point time_EndWeldingBA = std::chrono::steady_clock::now();
  1355. double timeWeldingBA = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndWeldingBA - time_StartWeldingBA).count();
  1356. vdWeldingBA_ms.push_back(timeWeldingBA);
  1357. #endif
  1358. //std::cout << "[Merge]: Welding bundle adjustment finished" << std::endl;
  1359. // Loop closed. Release Local Mapping.
  1360. mpLocalMapper->Release();
  1361. //Update the non critical area from the current map to the merged map
  1362. vector<KeyFrame*> vpCurrentMapKFs = pCurrentMap->GetAllKeyFrames();
  1363. vector<MapPoint*> vpCurrentMapMPs = pCurrentMap->GetAllMapPoints();
  1364. if(vpCurrentMapKFs.size() == 0){}
  1365. else {
  1366. if(mpTracker->mSensor == System::MONOCULAR)
  1367. {
  1368. unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
  1369. for(KeyFrame* pKFi : vpCurrentMapKFs)
  1370. {
  1371. if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap)
  1372. {
  1373. continue;
  1374. }
  1375. g2o::Sim3 g2oCorrectedSiw;
  1376. Sophus::SE3d Tiw = (pKFi->GetPose()).cast<double>();
  1377. g2o::Sim3 g2oSiw(Tiw.unit_quaternion(),Tiw.translation(),1.0);
  1378. //Pose without correction
  1379. vNonCorrectedSim3[pKFi]=g2oSiw;
  1380. Sophus::SE3d Tic = Tiw*Twc;
  1381. g2o::Sim3 g2oSim(Tic.unit_quaternion(),Tic.translation(),1.0);
  1382. g2oCorrectedSiw = g2oSim*mg2oMergeScw;
  1383. vCorrectedSim3[pKFi]=g2oCorrectedSiw;
  1384. // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation)
  1385. double s = g2oCorrectedSiw.scale();
  1386. pKFi->mfScale = s;
  1387. Sophus::SE3d correctedTiw(g2oCorrectedSiw.rotation(),g2oCorrectedSiw.translation() / s);
  1388. pKFi->mTcwBefMerge = pKFi->GetPose();
  1389. pKFi->mTwcBefMerge = pKFi->GetPoseInverse();
  1390. pKFi->SetPose(correctedTiw.cast<float>());
  1391. if(pCurrentMap->isImuInitialized())
  1392. {
  1393. Eigen::Quaternionf Rcor = (g2oCorrectedSiw.rotation().inverse() * vNonCorrectedSim3[pKFi].rotation()).cast<float>();
  1394. pKFi->SetVelocity(Rcor * pKFi->GetVelocity()); // TODO: should add here scale s
  1395. }
  1396. }
  1397. for(MapPoint* pMPi : vpCurrentMapMPs)
  1398. {
  1399. if(!pMPi || pMPi->isBad()|| pMPi->GetMap() != pCurrentMap)
  1400. continue;
  1401. KeyFrame* pKFref = pMPi->GetReferenceKeyFrame();
  1402. g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse();
  1403. g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref];
  1404. // Project with non-corrected pose and project back with corrected pose
  1405. Eigen::Vector3d P3Dw = pMPi->GetWorldPos().cast<double>();
  1406. Eigen::Vector3d eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oNonCorrectedSiw.map(P3Dw));
  1407. pMPi->SetWorldPos(eigCorrectedP3Dw.cast<float>());
  1408. pMPi->UpdateNormalAndDepth();
  1409. }
  1410. }
  1411. mpLocalMapper->RequestStop();
  1412. // Wait until Local Mapping has effectively stopped
  1413. while(!mpLocalMapper->isStopped())
  1414. {
  1415. usleep(1000);
  1416. }
  1417. // Optimize graph (and update the loop position for each element form the begining to the end)
  1418. if(mpTracker->mSensor != System::MONOCULAR)
  1419. {
  1420. Optimizer::OptimizeEssentialGraph(mpCurrentKF, vpMergeConnectedKFs, vpLocalCurrentWindowKFs, vpCurrentMapKFs, vpCurrentMapMPs);
  1421. }
  1422. {
  1423. // Get Merge Map Mutex
  1424. unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
  1425. unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
  1426. //std::cout << "Merge outside KFs: " << vpCurrentMapKFs.size() << std::endl;
  1427. for(KeyFrame* pKFi : vpCurrentMapKFs)
  1428. {
  1429. if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pCurrentMap)
  1430. {
  1431. continue;
  1432. }
  1433. //std::cout << "KF id: " << pKFi->mnId << std::endl;
  1434. // Make sure connections are updated
  1435. pKFi->UpdateMap(pMergeMap);
  1436. pMergeMap->AddKeyFrame(pKFi);
  1437. pCurrentMap->EraseKeyFrame(pKFi);
  1438. }
  1439. for(MapPoint* pMPi : vpCurrentMapMPs)
  1440. {
  1441. if(!pMPi || pMPi->isBad())
  1442. continue;
  1443. pMPi->UpdateMap(pMergeMap);
  1444. pMergeMap->AddMapPoint(pMPi);
  1445. pCurrentMap->EraseMapPoint(pMPi);
  1446. }
  1447. }
  1448. }
  1449. #ifdef REGISTER_TIMES
  1450. std::chrono::steady_clock::time_point time_EndOptEss = std::chrono::steady_clock::now();
  1451. double timeOptEss = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndOptEss - time_EndWeldingBA).count();
  1452. vdMergeOptEss_ms.push_back(timeOptEss);
  1453. #endif
  1454. mpLocalMapper->Release();
  1455. if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1)))
  1456. {
  1457. // Launch a new thread to perform Global Bundle Adjustment
  1458. mbRunningGBA = true;
  1459. mbFinishedGBA = false;
  1460. mbStopGBA = false;
  1461. mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment,this, pMergeMap, mpCurrentKF->mnId);
  1462. }
  1463. mpMergeMatchedKF->AddMergeEdge(mpCurrentKF);
  1464. mpCurrentKF->AddMergeEdge(mpMergeMatchedKF);
  1465. pCurrentMap->IncreaseChangeIndex();
  1466. pMergeMap->IncreaseChangeIndex();
  1467. mpAtlas->RemoveBadMaps();
  1468. }
  1469. void LoopClosing::MergeLocal2()
  1470. {
  1471. //cout << "Merge detected!!!!" << endl;
  1472. int numTemporalKFs = 11; //TODO (set by parameter): Temporal KFs in the local window if the map is inertial.
  1473. //Relationship to rebuild the essential graph, it is used two times, first in the local window and later in the rest of the map
  1474. KeyFrame* pNewChild;
  1475. KeyFrame* pNewParent;
  1476. vector<KeyFrame*> vpLocalCurrentWindowKFs;
  1477. vector<KeyFrame*> vpMergeConnectedKFs;
  1478. KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
  1479. // NonCorrectedSim3[mpCurrentKF]=mg2oLoopScw;
  1480. // Flag that is true only when we stopped a running BA, in this case we need relaunch at the end of the merge
  1481. bool bRelaunchBA = false;
  1482. //cout << "Check Full Bundle Adjustment" << endl;
  1483. // If a Global Bundle Adjustment is running, abort it
  1484. if(isRunningGBA())
  1485. {
  1486. unique_lock<mutex> lock(mMutexGBA);
  1487. mbStopGBA = true;
  1488. mnFullBAIdx++;
  1489. if(mpThreadGBA)
  1490. {
  1491. mpThreadGBA->detach();
  1492. delete mpThreadGBA;
  1493. }
  1494. bRelaunchBA = true;
  1495. }
  1496. //cout << "Request Stop Local Mapping" << endl;
  1497. mpLocalMapper->RequestStop();
  1498. // Wait until Local Mapping has effectively stopped
  1499. while(!mpLocalMapper->isStopped())
  1500. {
  1501. usleep(1000);
  1502. }
  1503. //cout << "Local Map stopped" << endl;
  1504. Map* pCurrentMap = mpCurrentKF->GetMap();
  1505. Map* pMergeMap = mpMergeMatchedKF->GetMap();
  1506. {
  1507. float s_on = mSold_new.scale();
  1508. Sophus::SE3f T_on(mSold_new.rotation().cast<float>(), mSold_new.translation().cast<float>());
  1509. unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
  1510. //cout << "KFs before empty: " << mpAtlas->GetCurrentMap()->KeyFramesInMap() << endl;
  1511. mpLocalMapper->EmptyQueue();
  1512. //cout << "KFs after empty: " << mpAtlas->GetCurrentMap()->KeyFramesInMap() << endl;
  1513. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  1514. //cout << "updating active map to merge reference" << endl;
  1515. //cout << "curr merge KF id: " << mpCurrentKF->mnId << endl;
  1516. //cout << "curr tracking KF id: " << mpTracker->GetLastKeyFrame()->mnId << endl;
  1517. bool bScaleVel=false;
  1518. if(s_on!=1)
  1519. bScaleVel=true;
  1520. mpAtlas->GetCurrentMap()->ApplyScaledRotation(T_on,s_on,bScaleVel);
  1521. mpTracker->UpdateFrameIMU(s_on,mpCurrentKF->GetImuBias(),mpTracker->GetLastKeyFrame());
  1522. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  1523. }
  1524. const int numKFnew=pCurrentMap->KeyFramesInMap();
  1525. if((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD)
  1526. && !pCurrentMap->GetIniertialBA2()){
  1527. // Map is not completly initialized
  1528. Eigen::Vector3d bg, ba;
  1529. bg << 0., 0., 0.;
  1530. ba << 0., 0., 0.;
  1531. Optimizer::InertialOptimization(pCurrentMap,bg,ba);
  1532. IMU::Bias b (ba[0],ba[1],ba[2],bg[0],bg[1],bg[2]);
  1533. unique_lock<mutex> lock(mpAtlas->GetCurrentMap()->mMutexMapUpdate);
  1534. mpTracker->UpdateFrameIMU(1.0f,b,mpTracker->GetLastKeyFrame());
  1535. // Set map initialized
  1536. pCurrentMap->SetIniertialBA2();
  1537. pCurrentMap->SetIniertialBA1();
  1538. pCurrentMap->SetImuInitialized();
  1539. }
  1540. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1541. // Load KFs and MPs from merge map
  1542. //cout << "updating current map" << endl;
  1543. {
  1544. // Get Merge Map Mutex (This section stops tracking!!)
  1545. unique_lock<mutex> currentLock(pCurrentMap->mMutexMapUpdate); // We update the current map with the Merge information
  1546. unique_lock<mutex> mergeLock(pMergeMap->mMutexMapUpdate); // We remove the Kfs and MPs in the merged area from the old map
  1547. vector<KeyFrame*> vpMergeMapKFs = pMergeMap->GetAllKeyFrames();
  1548. vector<MapPoint*> vpMergeMapMPs = pMergeMap->GetAllMapPoints();
  1549. for(KeyFrame* pKFi : vpMergeMapKFs)
  1550. {
  1551. if(!pKFi || pKFi->isBad() || pKFi->GetMap() != pMergeMap)
  1552. {
  1553. continue;
  1554. }
  1555. // Make sure connections are updated
  1556. pKFi->UpdateMap(pCurrentMap);
  1557. pCurrentMap->AddKeyFrame(pKFi);
  1558. pMergeMap->EraseKeyFrame(pKFi);
  1559. }
  1560. for(MapPoint* pMPi : vpMergeMapMPs)
  1561. {
  1562. if(!pMPi || pMPi->isBad() || pMPi->GetMap() != pMergeMap)
  1563. continue;
  1564. pMPi->UpdateMap(pCurrentMap);
  1565. pCurrentMap->AddMapPoint(pMPi);
  1566. pMergeMap->EraseMapPoint(pMPi);
  1567. }
  1568. // Save non corrected poses (already merged maps)
  1569. vector<KeyFrame*> vpKFs = pCurrentMap->GetAllKeyFrames();
  1570. for(KeyFrame* pKFi : vpKFs)
  1571. {
  1572. Sophus::SE3d Tiw = (pKFi->GetPose()).cast<double>();
  1573. g2o::Sim3 g2oSiw(Tiw.unit_quaternion(),Tiw.translation(),1.0);
  1574. NonCorrectedSim3[pKFi]=g2oSiw;
  1575. }
  1576. }
  1577. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1578. //cout << "end updating current map" << endl;
  1579. // Critical zone
  1580. //bool good = pCurrentMap->CheckEssentialGraph();
  1581. /*if(!good)
  1582. cout << "BAD ESSENTIAL GRAPH!!" << endl;*/
  1583. //cout << "Update essential graph" << endl;
  1584. // mpCurrentKF->UpdateConnections(); // to put at false mbFirstConnection
  1585. pMergeMap->GetOriginKF()->SetFirstConnection(false);
  1586. pNewChild = mpMergeMatchedKF->GetParent(); // Old parent, it will be the new child of this KF
  1587. pNewParent = mpMergeMatchedKF; // Old child, now it will be the parent of its own parent(we need eliminate this KF from children list in its old parent)
  1588. mpMergeMatchedKF->ChangeParent(mpCurrentKF);
  1589. while(pNewChild)
  1590. {
  1591. pNewChild->EraseChild(pNewParent); // We remove the relation between the old parent and the new for avoid loop
  1592. KeyFrame * pOldParent = pNewChild->GetParent();
  1593. pNewChild->ChangeParent(pNewParent);
  1594. pNewParent = pNewChild;
  1595. pNewChild = pOldParent;
  1596. }
  1597. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1598. //cout << "end update essential graph" << endl;
  1599. /*good = pCurrentMap->CheckEssentialGraph();
  1600. if(!good)
  1601. cout << "BAD ESSENTIAL GRAPH 1!!" << endl;*/
  1602. //cout << "Update relationship between KFs" << endl;
  1603. vector<MapPoint*> vpCheckFuseMapPoint; // MapPoint vector from current map to allow to fuse duplicated points with the old map (merge)
  1604. vector<KeyFrame*> vpCurrentConnectedKFs;
  1605. mvpMergeConnectedKFs.push_back(mpMergeMatchedKF);
  1606. vector<KeyFrame*> aux = mpMergeMatchedKF->GetVectorCovisibleKeyFrames();
  1607. mvpMergeConnectedKFs.insert(mvpMergeConnectedKFs.end(), aux.begin(), aux.end());
  1608. if (mvpMergeConnectedKFs.size()>6)
  1609. mvpMergeConnectedKFs.erase(mvpMergeConnectedKFs.begin()+6,mvpMergeConnectedKFs.end());
  1610. /*mvpMergeConnectedKFs = mpMergeMatchedKF->GetVectorCovisibleKeyFrames();
  1611. mvpMergeConnectedKFs.push_back(mpMergeMatchedKF);*/
  1612. mpCurrentKF->UpdateConnections();
  1613. vpCurrentConnectedKFs.push_back(mpCurrentKF);
  1614. /*vpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames();
  1615. vpCurrentConnectedKFs.push_back(mpCurrentKF);*/
  1616. aux = mpCurrentKF->GetVectorCovisibleKeyFrames();
  1617. vpCurrentConnectedKFs.insert(vpCurrentConnectedKFs.end(), aux.begin(), aux.end());
  1618. if (vpCurrentConnectedKFs.size()>6)
  1619. vpCurrentConnectedKFs.erase(vpCurrentConnectedKFs.begin()+6,vpCurrentConnectedKFs.end());
  1620. set<MapPoint*> spMapPointMerge;
  1621. for(KeyFrame* pKFi : mvpMergeConnectedKFs)
  1622. {
  1623. set<MapPoint*> vpMPs = pKFi->GetMapPoints();
  1624. spMapPointMerge.insert(vpMPs.begin(),vpMPs.end());
  1625. if(spMapPointMerge.size()>1000)
  1626. break;
  1627. }
  1628. /*cout << "vpCurrentConnectedKFs.size() " << vpCurrentConnectedKFs.size() << endl;
  1629. cout << "mvpMergeConnectedKFs.size() " << mvpMergeConnectedKFs.size() << endl;
  1630. cout << "spMapPointMerge.size() " << spMapPointMerge.size() << endl;*/
  1631. vpCheckFuseMapPoint.reserve(spMapPointMerge.size());
  1632. std::copy(spMapPointMerge.begin(), spMapPointMerge.end(), std::back_inserter(vpCheckFuseMapPoint));
  1633. //cout << "Finished to update relationship between KFs" << endl;
  1634. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1635. /*good = pCurrentMap->CheckEssentialGraph();
  1636. if(!good)
  1637. cout << "BAD ESSENTIAL GRAPH 2!!" << endl;*/
  1638. //cout << "start SearchAndFuse" << endl;
  1639. SearchAndFuse(vpCurrentConnectedKFs, vpCheckFuseMapPoint);
  1640. //cout << "end SearchAndFuse" << endl;
  1641. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1642. /*good = pCurrentMap->CheckEssentialGraph();
  1643. if(!good)
  1644. cout << "BAD ESSENTIAL GRAPH 3!!" << endl;
  1645. cout << "Init to update connections" << endl;*/
  1646. for(KeyFrame* pKFi : vpCurrentConnectedKFs)
  1647. {
  1648. if(!pKFi || pKFi->isBad())
  1649. continue;
  1650. pKFi->UpdateConnections();
  1651. }
  1652. for(KeyFrame* pKFi : mvpMergeConnectedKFs)
  1653. {
  1654. if(!pKFi || pKFi->isBad())
  1655. continue;
  1656. pKFi->UpdateConnections();
  1657. }
  1658. //cout << "end update connections" << endl;
  1659. //cout << "MergeMap init ID: " << pMergeMap->GetInitKFid() << " CurrMap init ID: " << pCurrentMap->GetInitKFid() << endl;
  1660. /*good = pCurrentMap->CheckEssentialGraph();
  1661. if(!good)
  1662. cout << "BAD ESSENTIAL GRAPH 4!!" << endl;*/
  1663. // TODO Check: If new map is too small, we suppose that not informaiton can be propagated from new to old map
  1664. if (numKFnew<10){
  1665. mpLocalMapper->Release();
  1666. return;
  1667. }
  1668. /*good = pCurrentMap->CheckEssentialGraph();
  1669. if(!good)
  1670. cout << "BAD ESSENTIAL GRAPH 5!!" << endl;*/
  1671. // Perform BA
  1672. bool bStopFlag=false;
  1673. KeyFrame* pCurrKF = mpTracker->GetLastKeyFrame();
  1674. //cout << "start MergeInertialBA" << endl;
  1675. Optimizer::MergeInertialBA(pCurrKF, mpMergeMatchedKF, &bStopFlag, pCurrentMap,CorrectedSim3);
  1676. //cout << "end MergeInertialBA" << endl;
  1677. /*good = pCurrentMap->CheckEssentialGraph();
  1678. if(!good)
  1679. cout << "BAD ESSENTIAL GRAPH 6!!" << endl;*/
  1680. // Release Local Mapping.
  1681. mpLocalMapper->Release();
  1682. return;
  1683. }
  1684. void LoopClosing::CheckObservations(set<KeyFrame*> &spKFsMap1, set<KeyFrame*> &spKFsMap2)
  1685. {
  1686. cout << "----------------------" << endl;
  1687. for(KeyFrame* pKFi1 : spKFsMap1)
  1688. {
  1689. map<KeyFrame*, int> mMatchedMP;
  1690. set<MapPoint*> spMPs = pKFi1->GetMapPoints();
  1691. for(MapPoint* pMPij : spMPs)
  1692. {
  1693. if(!pMPij || pMPij->isBad())
  1694. {
  1695. continue;
  1696. }
  1697. map<KeyFrame*, tuple<int,int>> mMPijObs = pMPij->GetObservations();
  1698. for(KeyFrame* pKFi2 : spKFsMap2)
  1699. {
  1700. if(mMPijObs.find(pKFi2) != mMPijObs.end())
  1701. {
  1702. if(mMatchedMP.find(pKFi2) != mMatchedMP.end())
  1703. {
  1704. mMatchedMP[pKFi2] = mMatchedMP[pKFi2] + 1;
  1705. }
  1706. else
  1707. {
  1708. mMatchedMP[pKFi2] = 1;
  1709. }
  1710. }
  1711. }
  1712. }
  1713. if(mMatchedMP.size() == 0)
  1714. {
  1715. cout << "CHECK-OBS: KF " << pKFi1->mnId << " has not any matched MP with the other map" << endl;
  1716. }
  1717. else
  1718. {
  1719. cout << "CHECK-OBS: KF " << pKFi1->mnId << " has matched MP with " << mMatchedMP.size() << " KF from the other map" << endl;
  1720. for(pair<KeyFrame*, int> matchedKF : mMatchedMP)
  1721. {
  1722. cout << " -KF: " << matchedKF.first->mnId << ", Number of matches: " << matchedKF.second << endl;
  1723. }
  1724. }
  1725. }
  1726. cout << "----------------------" << endl;
  1727. }
  1728. void LoopClosing::SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap, vector<MapPoint*> &vpMapPoints)
  1729. {
  1730. ORBmatcher matcher(0.8);
  1731. int total_replaces = 0;
  1732. //cout << "[FUSE]: Initially there are " << vpMapPoints.size() << " MPs" << endl;
  1733. //cout << "FUSE: Intially there are " << CorrectedPosesMap.size() << " KFs" << endl;
  1734. for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++)
  1735. {
  1736. int num_replaces = 0;
  1737. KeyFrame* pKFi = mit->first;
  1738. Map* pMap = pKFi->GetMap();
  1739. g2o::Sim3 g2oScw = mit->second;
  1740. Sophus::Sim3f Scw = Converter::toSophus(g2oScw);
  1741. vector<MapPoint*> vpReplacePoints(vpMapPoints.size(),static_cast<MapPoint*>(NULL));
  1742. int numFused = matcher.Fuse(pKFi,Scw,vpMapPoints,4,vpReplacePoints);
  1743. // Get Map Mutex
  1744. unique_lock<mutex> lock(pMap->mMutexMapUpdate);
  1745. const int nLP = vpMapPoints.size();
  1746. for(int i=0; i<nLP;i++)
  1747. {
  1748. MapPoint* pRep = vpReplacePoints[i];
  1749. if(pRep)
  1750. {
  1751. num_replaces += 1;
  1752. pRep->Replace(vpMapPoints[i]);
  1753. }
  1754. }
  1755. total_replaces += num_replaces;
  1756. }
  1757. //cout << "[FUSE]: " << total_replaces << " MPs had been fused" << endl;
  1758. }
  1759. void LoopClosing::SearchAndFuse(const vector<KeyFrame*> &vConectedKFs, vector<MapPoint*> &vpMapPoints)
  1760. {
  1761. ORBmatcher matcher(0.8);
  1762. int total_replaces = 0;
  1763. //cout << "FUSE-POSE: Initially there are " << vpMapPoints.size() << " MPs" << endl;
  1764. //cout << "FUSE-POSE: Intially there are " << vConectedKFs.size() << " KFs" << endl;
  1765. for(auto mit=vConectedKFs.begin(), mend=vConectedKFs.end(); mit!=mend;mit++)
  1766. {
  1767. int num_replaces = 0;
  1768. KeyFrame* pKF = (*mit);
  1769. Map* pMap = pKF->GetMap();
  1770. Sophus::SE3f Tcw = pKF->GetPose();
  1771. Sophus::Sim3f Scw(Tcw.unit_quaternion(),Tcw.translation());
  1772. Scw.setScale(1.f);
  1773. /*std::cout << "These should be zeros: " <<
  1774. Scw.rotationMatrix() - Tcw.rotationMatrix() << std::endl <<
  1775. Scw.translation() - Tcw.translation() << std::endl <<
  1776. Scw.scale() - 1.f << std::endl;*/
  1777. vector<MapPoint*> vpReplacePoints(vpMapPoints.size(),static_cast<MapPoint*>(NULL));
  1778. matcher.Fuse(pKF,Scw,vpMapPoints,4,vpReplacePoints);
  1779. // Get Map Mutex
  1780. unique_lock<mutex> lock(pMap->mMutexMapUpdate);
  1781. const int nLP = vpMapPoints.size();
  1782. for(int i=0; i<nLP;i++)
  1783. {
  1784. MapPoint* pRep = vpReplacePoints[i];
  1785. if(pRep)
  1786. {
  1787. num_replaces += 1;
  1788. pRep->Replace(vpMapPoints[i]);
  1789. }
  1790. }
  1791. /*cout << "FUSE-POSE: KF " << pKF->mnId << " ->" << num_replaces << " MPs fused" << endl;
  1792. total_replaces += num_replaces;*/
  1793. }
  1794. //cout << "FUSE-POSE: " << total_replaces << " MPs had been fused" << endl;
  1795. }
  1796. void LoopClosing::RequestReset()
  1797. {
  1798. {
  1799. unique_lock<mutex> lock(mMutexReset);
  1800. mbResetRequested = true;
  1801. }
  1802. while(1)
  1803. {
  1804. {
  1805. unique_lock<mutex> lock2(mMutexReset);
  1806. if(!mbResetRequested)
  1807. break;
  1808. }
  1809. usleep(5000);
  1810. }
  1811. }
  1812. void LoopClosing::RequestResetActiveMap(Map *pMap)
  1813. {
  1814. {
  1815. unique_lock<mutex> lock(mMutexReset);
  1816. mbResetActiveMapRequested = true;
  1817. mpMapToReset = pMap;
  1818. }
  1819. while(1)
  1820. {
  1821. {
  1822. unique_lock<mutex> lock2(mMutexReset);
  1823. if(!mbResetActiveMapRequested)
  1824. break;
  1825. }
  1826. usleep(3000);
  1827. }
  1828. }
  1829. void LoopClosing::ResetIfRequested()
  1830. {
  1831. unique_lock<mutex> lock(mMutexReset);
  1832. if(mbResetRequested)
  1833. {
  1834. cout << "Loop closer reset requested..." << endl;
  1835. mlpLoopKeyFrameQueue.clear();
  1836. mLastLoopKFid=0; //TODO old variable, it is not use in the new algorithm
  1837. mbResetRequested=false;
  1838. mbResetActiveMapRequested = false;
  1839. }
  1840. else if(mbResetActiveMapRequested)
  1841. {
  1842. for (list<KeyFrame*>::const_iterator it=mlpLoopKeyFrameQueue.begin(); it != mlpLoopKeyFrameQueue.end();)
  1843. {
  1844. KeyFrame* pKFi = *it;
  1845. if(pKFi->GetMap() == mpMapToReset)
  1846. {
  1847. it = mlpLoopKeyFrameQueue.erase(it);
  1848. }
  1849. else
  1850. ++it;
  1851. }
  1852. mLastLoopKFid=mpAtlas->GetLastInitKFid(); //TODO old variable, it is not use in the new algorithm
  1853. mbResetActiveMapRequested=false;
  1854. }
  1855. }
  1856. void LoopClosing::RunGlobalBundleAdjustment(Map* pActiveMap, unsigned long nLoopKF)
  1857. {
  1858. Verbose::PrintMess("Starting Global Bundle Adjustment", Verbose::VERBOSITY_NORMAL);
  1859. #ifdef REGISTER_TIMES
  1860. std::chrono::steady_clock::time_point time_StartFGBA = std::chrono::steady_clock::now();
  1861. nFGBA_exec += 1;
  1862. vnGBAKFs.push_back(pActiveMap->GetAllKeyFrames().size());
  1863. vnGBAMPs.push_back(pActiveMap->GetAllMapPoints().size());
  1864. #endif
  1865. const bool bImuInit = pActiveMap->isImuInitialized();
  1866. if(!bImuInit)
  1867. Optimizer::GlobalBundleAdjustemnt(pActiveMap,10,&mbStopGBA,nLoopKF,false);
  1868. else
  1869. Optimizer::FullInertialBA(pActiveMap,7,false,nLoopKF,&mbStopGBA);
  1870. #ifdef REGISTER_TIMES
  1871. std::chrono::steady_clock::time_point time_EndGBA = std::chrono::steady_clock::now();
  1872. double timeGBA = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndGBA - time_StartFGBA).count();
  1873. vdGBA_ms.push_back(timeGBA);
  1874. if(mbStopGBA)
  1875. {
  1876. nFGBA_abort += 1;
  1877. }
  1878. #endif
  1879. int idx = mnFullBAIdx;
  1880. // Optimizer::GlobalBundleAdjustemnt(mpMap,10,&mbStopGBA,nLoopKF,false);
  1881. // Update all MapPoints and KeyFrames
  1882. // Local Mapping was active during BA, that means that there might be new keyframes
  1883. // not included in the Global BA and they are not consistent with the updated map.
  1884. // We need to propagate the correction through the spanning tree
  1885. {
  1886. unique_lock<mutex> lock(mMutexGBA);
  1887. if(idx!=mnFullBAIdx)
  1888. return;
  1889. if(!bImuInit && pActiveMap->isImuInitialized())
  1890. return;
  1891. if(!mbStopGBA)
  1892. {
  1893. Verbose::PrintMess("Global Bundle Adjustment finished", Verbose::VERBOSITY_NORMAL);
  1894. Verbose::PrintMess("Updating map ...", Verbose::VERBOSITY_NORMAL);
  1895. mpLocalMapper->RequestStop();
  1896. // Wait until Local Mapping has effectively stopped
  1897. while(!mpLocalMapper->isStopped() && !mpLocalMapper->isFinished())
  1898. {
  1899. usleep(1000);
  1900. }
  1901. // Get Map Mutex
  1902. unique_lock<mutex> lock(pActiveMap->mMutexMapUpdate);
  1903. // cout << "LC: Update Map Mutex adquired" << endl;
  1904. //pActiveMap->PrintEssentialGraph();
  1905. // Correct keyframes starting at map first keyframe
  1906. list<KeyFrame*> lpKFtoCheck(pActiveMap->mvpKeyFrameOrigins.begin(),pActiveMap->mvpKeyFrameOrigins.end());
  1907. while(!lpKFtoCheck.empty())
  1908. {
  1909. KeyFrame* pKF = lpKFtoCheck.front();
  1910. const set<KeyFrame*> sChilds = pKF->GetChilds();
  1911. //cout << "---Updating KF " << pKF->mnId << " with " << sChilds.size() << " childs" << endl;
  1912. //cout << " KF mnBAGlobalForKF: " << pKF->mnBAGlobalForKF << endl;
  1913. Sophus::SE3f Twc = pKF->GetPoseInverse();
  1914. //cout << "Twc: " << Twc << endl;
  1915. //cout << "GBA: Correct KeyFrames" << endl;
  1916. for(set<KeyFrame*>::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++)
  1917. {
  1918. KeyFrame* pChild = *sit;
  1919. if(!pChild || pChild->isBad())
  1920. continue;
  1921. if(pChild->mnBAGlobalForKF!=nLoopKF)
  1922. {
  1923. //cout << "++++New child with flag " << pChild->mnBAGlobalForKF << "; LoopKF: " << nLoopKF << endl;
  1924. //cout << " child id: " << pChild->mnId << endl;
  1925. Sophus::SE3f Tchildc = pChild->GetPose() * Twc;
  1926. //cout << "Child pose: " << Tchildc << endl;
  1927. //cout << "pKF->mTcwGBA: " << pKF->mTcwGBA << endl;
  1928. pChild->mTcwGBA = Tchildc * pKF->mTcwGBA;//*Tcorc*pKF->mTcwGBA;
  1929. Sophus::SO3f Rcor = pChild->mTcwGBA.so3().inverse() * pChild->GetPose().so3();
  1930. if(pChild->isVelocitySet()){
  1931. pChild->mVwbGBA = Rcor * pChild->GetVelocity();
  1932. }
  1933. else
  1934. Verbose::PrintMess("Child velocity empty!! ", Verbose::VERBOSITY_NORMAL);
  1935. //cout << "Child bias: " << pChild->GetImuBias() << endl;
  1936. pChild->mBiasGBA = pChild->GetImuBias();
  1937. pChild->mnBAGlobalForKF = nLoopKF;
  1938. }
  1939. lpKFtoCheck.push_back(pChild);
  1940. }
  1941. //cout << "-------Update pose" << endl;
  1942. pKF->mTcwBefGBA = pKF->GetPose();
  1943. //cout << "pKF->mTcwBefGBA: " << pKF->mTcwBefGBA << endl;
  1944. pKF->SetPose(pKF->mTcwGBA);
  1945. /*cv::Mat Tco_cn = pKF->mTcwBefGBA * pKF->mTcwGBA.inv();
  1946. cv::Vec3d trasl = Tco_cn.rowRange(0,3).col(3);
  1947. double dist = cv::norm(trasl);
  1948. cout << "GBA: KF " << pKF->mnId << " had been moved " << dist << " meters" << endl;
  1949. double desvX = 0;
  1950. double desvY = 0;
  1951. double desvZ = 0;
  1952. if(pKF->mbHasHessian)
  1953. {
  1954. cv::Mat hessianInv = pKF->mHessianPose.inv();
  1955. double covX = hessianInv.at<double>(3,3);
  1956. desvX = std::sqrt(covX);
  1957. double covY = hessianInv.at<double>(4,4);
  1958. desvY = std::sqrt(covY);
  1959. double covZ = hessianInv.at<double>(5,5);
  1960. desvZ = std::sqrt(covZ);
  1961. pKF->mbHasHessian = false;
  1962. }
  1963. if(dist > 1)
  1964. {
  1965. cout << "--To much distance correction: It has " << pKF->GetConnectedKeyFrames().size() << " connected KFs" << endl;
  1966. cout << "--It has " << pKF->GetCovisiblesByWeight(80).size() << " connected KF with 80 common matches or more" << endl;
  1967. cout << "--It has " << pKF->GetCovisiblesByWeight(50).size() << " connected KF with 50 common matches or more" << endl;
  1968. cout << "--It has " << pKF->GetCovisiblesByWeight(20).size() << " connected KF with 20 common matches or more" << endl;
  1969. cout << "--STD in meters(x, y, z): " << desvX << ", " << desvY << ", " << desvZ << endl;
  1970. string strNameFile = pKF->mNameFile;
  1971. cv::Mat imLeft = cv::imread(strNameFile, CV_LOAD_IMAGE_UNCHANGED);
  1972. cv::cvtColor(imLeft, imLeft, CV_GRAY2BGR);
  1973. vector<MapPoint*> vpMapPointsKF = pKF->GetMapPointMatches();
  1974. int num_MPs = 0;
  1975. for(int i=0; i<vpMapPointsKF.size(); ++i)
  1976. {
  1977. if(!vpMapPointsKF[i] || vpMapPointsKF[i]->isBad())
  1978. {
  1979. continue;
  1980. }
  1981. num_MPs += 1;
  1982. string strNumOBs = to_string(vpMapPointsKF[i]->Observations());
  1983. cv::circle(imLeft, pKF->mvKeys[i].pt, 2, cv::Scalar(0, 255, 0));
  1984. cv::putText(imLeft, strNumOBs, pKF->mvKeys[i].pt, CV_FONT_HERSHEY_DUPLEX, 1, cv::Scalar(255, 0, 0));
  1985. }
  1986. cout << "--It has " << num_MPs << " MPs matched in the map" << endl;
  1987. string namefile = "./test_GBA/GBA_" + to_string(nLoopKF) + "_KF" + to_string(pKF->mnId) +"_D" + to_string(dist) +".png";
  1988. cv::imwrite(namefile, imLeft);
  1989. }*/
  1990. if(pKF->bImu)
  1991. {
  1992. //cout << "-------Update inertial values" << endl;
  1993. pKF->mVwbBefGBA = pKF->GetVelocity();
  1994. //if (pKF->mVwbGBA.empty())
  1995. // Verbose::PrintMess("pKF->mVwbGBA is empty", Verbose::VERBOSITY_NORMAL);
  1996. //assert(!pKF->mVwbGBA.empty());
  1997. pKF->SetVelocity(pKF->mVwbGBA);
  1998. pKF->SetNewBias(pKF->mBiasGBA);
  1999. }
  2000. lpKFtoCheck.pop_front();
  2001. }
  2002. //cout << "GBA: Correct MapPoints" << endl;
  2003. // Correct MapPoints
  2004. const vector<MapPoint*> vpMPs = pActiveMap->GetAllMapPoints();
  2005. for(size_t i=0; i<vpMPs.size(); i++)
  2006. {
  2007. MapPoint* pMP = vpMPs[i];
  2008. if(pMP->isBad())
  2009. continue;
  2010. if(pMP->mnBAGlobalForKF==nLoopKF)
  2011. {
  2012. // If optimized by Global BA, just update
  2013. pMP->SetWorldPos(pMP->mPosGBA);
  2014. }
  2015. else
  2016. {
  2017. // Update according to the correction of its reference keyframe
  2018. KeyFrame* pRefKF = pMP->GetReferenceKeyFrame();
  2019. if(pRefKF->mnBAGlobalForKF!=nLoopKF)
  2020. continue;
  2021. /*if(pRefKF->mTcwBefGBA.empty())
  2022. continue;*/
  2023. // Map to non-corrected camera
  2024. // cv::Mat Rcw = pRefKF->mTcwBefGBA.rowRange(0,3).colRange(0,3);
  2025. // cv::Mat tcw = pRefKF->mTcwBefGBA.rowRange(0,3).col(3);
  2026. Eigen::Vector3f Xc = pRefKF->mTcwBefGBA * pMP->GetWorldPos();
  2027. // Backproject using corrected camera
  2028. pMP->SetWorldPos(pRefKF->GetPoseInverse() * Xc);
  2029. }
  2030. }
  2031. pActiveMap->InformNewBigChange();
  2032. pActiveMap->IncreaseChangeIndex();
  2033. // TODO Check this update
  2034. // mpTracker->UpdateFrameIMU(1.0f, mpTracker->GetLastKeyFrame()->GetImuBias(), mpTracker->GetLastKeyFrame());
  2035. mpLocalMapper->Release();
  2036. #ifdef REGISTER_TIMES
  2037. std::chrono::steady_clock::time_point time_EndUpdateMap = std::chrono::steady_clock::now();
  2038. double timeUpdateMap = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndUpdateMap - time_EndGBA).count();
  2039. vdUpdateMap_ms.push_back(timeUpdateMap);
  2040. double timeFGBA = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(time_EndUpdateMap - time_StartFGBA).count();
  2041. vdFGBATotal_ms.push_back(timeFGBA);
  2042. #endif
  2043. Verbose::PrintMess("Map updated!", Verbose::VERBOSITY_NORMAL);
  2044. }
  2045. mbFinishedGBA = true;
  2046. mbRunningGBA = false;
  2047. }
  2048. }
  2049. void LoopClosing::RequestFinish()
  2050. {
  2051. unique_lock<mutex> lock(mMutexFinish);
  2052. // cout << "LC: Finish requested" << endl;
  2053. mbFinishRequested = true;
  2054. }
  2055. bool LoopClosing::CheckFinish()
  2056. {
  2057. unique_lock<mutex> lock(mMutexFinish);
  2058. return mbFinishRequested;
  2059. }
  2060. void LoopClosing::SetFinish()
  2061. {
  2062. unique_lock<mutex> lock(mMutexFinish);
  2063. mbFinished = true;
  2064. }
  2065. bool LoopClosing::isFinished()
  2066. {
  2067. unique_lock<mutex> lock(mMutexFinish);
  2068. return mbFinished;
  2069. }
  2070. } //namespace ORB_SLAM