MapPoint.cc 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include "MapPoint.h"
  19. #include "ORBmatcher.h"
  20. #include<mutex>
  21. namespace ORB_SLAM3
  22. {
  23. long unsigned int MapPoint::nNextId=0;
  24. mutex MapPoint::mGlobalMutex;
  25. MapPoint::MapPoint():
  26. mnFirstKFid(0), mnFirstFrame(0), nObs(0), mnTrackReferenceForFrame(0),
  27. mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0),
  28. mnCorrectedReference(0), mnBAGlobalForKF(0), mnVisible(1), mnFound(1), mbBad(false),
  29. mpReplaced(static_cast<MapPoint*>(NULL))
  30. {
  31. mpReplaced = static_cast<MapPoint*>(NULL);
  32. }
  33. MapPoint::MapPoint(const cv::Mat &Pos, KeyFrame *pRefKF, Map* pMap):
  34. mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0),
  35. mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0),
  36. mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false),
  37. mpReplaced(static_cast<MapPoint*>(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap),
  38. mnOriginMapId(pMap->GetId())
  39. {
  40. Pos.copyTo(mWorldPos);
  41. mNormalVector = cv::Mat::zeros(3,1,CV_32F);
  42. mbTrackInViewR = false;
  43. mbTrackInView = false;
  44. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  45. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  46. mnId=nNextId++;
  47. }
  48. MapPoint::MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap):
  49. mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0),
  50. mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0),
  51. mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false),
  52. mpReplaced(static_cast<MapPoint*>(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap),
  53. mnOriginMapId(pMap->GetId())
  54. {
  55. mInvDepth=invDepth;
  56. mInitU=(double)uv_init.x;
  57. mInitV=(double)uv_init.y;
  58. mpHostKF = pHostKF;
  59. mNormalVector = cv::Mat::zeros(3,1,CV_32F);
  60. // Worldpos is not set
  61. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  62. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  63. mnId=nNextId++;
  64. }
  65. MapPoint::MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF):
  66. mnFirstKFid(-1), mnFirstFrame(pFrame->mnId), nObs(0), mnTrackReferenceForFrame(0), mnLastFrameSeen(0),
  67. mnBALocalForKF(0), mnFuseCandidateForKF(0),mnLoopPointForKF(0), mnCorrectedByKF(0),
  68. mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(static_cast<KeyFrame*>(NULL)), mnVisible(1),
  69. mnFound(1), mbBad(false), mpReplaced(NULL), mpMap(pMap), mnOriginMapId(pMap->GetId())
  70. {
  71. Pos.copyTo(mWorldPos);
  72. cv::Mat Ow;
  73. if(pFrame -> Nleft == -1 || idxF < pFrame -> Nleft){
  74. Ow = pFrame->GetCameraCenter();
  75. }
  76. else{
  77. cv::Mat Rwl = pFrame -> mRwc;
  78. cv::Mat tlr = pFrame -> mTlr.col(3);
  79. cv::Mat twl = pFrame -> mOw;
  80. Ow = Rwl * tlr + twl;
  81. }
  82. mNormalVector = mWorldPos - Ow;
  83. mNormalVector = mNormalVector/cv::norm(mNormalVector);
  84. cv::Mat PC = Pos - Ow;
  85. const float dist = cv::norm(PC);
  86. const int level = (pFrame -> Nleft == -1) ? pFrame->mvKeysUn[idxF].octave
  87. : (idxF < pFrame -> Nleft) ? pFrame->mvKeys[idxF].octave
  88. : pFrame -> mvKeysRight[idxF].octave;
  89. const float levelScaleFactor = pFrame->mvScaleFactors[level];
  90. const int nLevels = pFrame->mnScaleLevels;
  91. mfMaxDistance = dist*levelScaleFactor;
  92. mfMinDistance = mfMaxDistance/pFrame->mvScaleFactors[nLevels-1];
  93. pFrame->mDescriptors.row(idxF).copyTo(mDescriptor);
  94. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  95. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  96. mnId=nNextId++;
  97. }
  98. void MapPoint::SetWorldPos(const cv::Mat &Pos)
  99. {
  100. unique_lock<mutex> lock2(mGlobalMutex);
  101. unique_lock<mutex> lock(mMutexPos);
  102. Pos.copyTo(mWorldPos);
  103. }
  104. cv::Mat MapPoint::GetWorldPos()
  105. {
  106. unique_lock<mutex> lock(mMutexPos);
  107. return mWorldPos.clone();
  108. }
  109. cv::Mat MapPoint::GetNormal()
  110. {
  111. unique_lock<mutex> lock(mMutexPos);
  112. return mNormalVector.clone();
  113. }
  114. KeyFrame* MapPoint::GetReferenceKeyFrame()
  115. {
  116. unique_lock<mutex> lock(mMutexFeatures);
  117. return mpRefKF;
  118. }
  119. void MapPoint::AddObservation(KeyFrame* pKF, int idx)
  120. {
  121. unique_lock<mutex> lock(mMutexFeatures);
  122. tuple<int,int> indexes;
  123. if(mObservations.count(pKF)){
  124. indexes = mObservations[pKF];
  125. }
  126. else{
  127. indexes = tuple<int,int>(-1,-1);
  128. }
  129. if(pKF -> NLeft != -1 && idx >= pKF -> NLeft){
  130. get<1>(indexes) = idx;
  131. }
  132. else{
  133. get<0>(indexes) = idx;
  134. }
  135. mObservations[pKF]=indexes;
  136. if(!pKF->mpCamera2 && pKF->mvuRight[idx]>=0)
  137. nObs+=2;
  138. else
  139. nObs++;
  140. }
  141. void MapPoint::EraseObservation(KeyFrame* pKF)
  142. {
  143. bool bBad=false;
  144. {
  145. unique_lock<mutex> lock(mMutexFeatures);
  146. if(mObservations.count(pKF))
  147. {
  148. //int idx = mObservations[pKF];
  149. tuple<int,int> indexes = mObservations[pKF];
  150. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  151. if(leftIndex != -1){
  152. if(!pKF->mpCamera2 && pKF->mvuRight[leftIndex]>=0)
  153. nObs-=2;
  154. else
  155. nObs--;
  156. }
  157. if(rightIndex != -1){
  158. nObs--;
  159. }
  160. mObservations.erase(pKF);
  161. if(mpRefKF==pKF)
  162. mpRefKF=mObservations.begin()->first;
  163. // If only 2 observations or less, discard point
  164. if(nObs<=2)
  165. bBad=true;
  166. }
  167. }
  168. if(bBad)
  169. SetBadFlag();
  170. }
  171. std::map<KeyFrame*, std::tuple<int,int>> MapPoint::GetObservations()
  172. {
  173. unique_lock<mutex> lock(mMutexFeatures);
  174. return mObservations;
  175. }
  176. int MapPoint::Observations()
  177. {
  178. unique_lock<mutex> lock(mMutexFeatures);
  179. return nObs;
  180. }
  181. void MapPoint::SetBadFlag()
  182. {
  183. map<KeyFrame*, tuple<int,int>> obs;
  184. {
  185. unique_lock<mutex> lock1(mMutexFeatures);
  186. unique_lock<mutex> lock2(mMutexPos);
  187. mbBad=true;
  188. obs = mObservations;
  189. mObservations.clear();
  190. }
  191. for(map<KeyFrame*, tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  192. {
  193. KeyFrame* pKF = mit->first;
  194. int leftIndex = get<0>(mit -> second), rightIndex = get<1>(mit -> second);
  195. if(leftIndex != -1){
  196. pKF->EraseMapPointMatch(leftIndex);
  197. }
  198. if(rightIndex != -1){
  199. pKF->EraseMapPointMatch(rightIndex);
  200. }
  201. }
  202. mpMap->EraseMapPoint(this);
  203. }
  204. MapPoint* MapPoint::GetReplaced()
  205. {
  206. unique_lock<mutex> lock1(mMutexFeatures);
  207. unique_lock<mutex> lock2(mMutexPos);
  208. return mpReplaced;
  209. }
  210. void MapPoint::Replace(MapPoint* pMP)
  211. {
  212. if(pMP->mnId==this->mnId)
  213. return;
  214. int nvisible, nfound;
  215. map<KeyFrame*,tuple<int,int>> obs;
  216. {
  217. unique_lock<mutex> lock1(mMutexFeatures);
  218. unique_lock<mutex> lock2(mMutexPos);
  219. obs=mObservations;
  220. mObservations.clear();
  221. mbBad=true;
  222. nvisible = mnVisible;
  223. nfound = mnFound;
  224. mpReplaced = pMP;
  225. }
  226. for(map<KeyFrame*,tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  227. {
  228. // Replace measurement in keyframe
  229. KeyFrame* pKF = mit->first;
  230. tuple<int,int> indexes = mit -> second;
  231. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  232. if(!pMP->IsInKeyFrame(pKF))
  233. {
  234. if(leftIndex != -1){
  235. pKF->ReplaceMapPointMatch(leftIndex, pMP);
  236. pMP->AddObservation(pKF,leftIndex);
  237. }
  238. if(rightIndex != -1){
  239. pKF->ReplaceMapPointMatch(rightIndex, pMP);
  240. pMP->AddObservation(pKF,rightIndex);
  241. }
  242. }
  243. else
  244. {
  245. if(leftIndex != -1){
  246. pKF->EraseMapPointMatch(leftIndex);
  247. }
  248. if(rightIndex != -1){
  249. pKF->EraseMapPointMatch(rightIndex);
  250. }
  251. }
  252. }
  253. pMP->IncreaseFound(nfound);
  254. pMP->IncreaseVisible(nvisible);
  255. pMP->ComputeDistinctiveDescriptors();
  256. mpMap->EraseMapPoint(this);
  257. }
  258. bool MapPoint::isBad()
  259. {
  260. unique_lock<mutex> lock1(mMutexFeatures,std::defer_lock);
  261. unique_lock<mutex> lock2(mMutexPos,std::defer_lock);
  262. lock(lock1, lock2);
  263. return mbBad;
  264. }
  265. void MapPoint::IncreaseVisible(int n)
  266. {
  267. unique_lock<mutex> lock(mMutexFeatures);
  268. mnVisible+=n;
  269. }
  270. void MapPoint::IncreaseFound(int n)
  271. {
  272. unique_lock<mutex> lock(mMutexFeatures);
  273. mnFound+=n;
  274. }
  275. float MapPoint::GetFoundRatio()
  276. {
  277. unique_lock<mutex> lock(mMutexFeatures);
  278. return static_cast<float>(mnFound)/mnVisible;
  279. }
  280. void MapPoint::ComputeDistinctiveDescriptors()
  281. {
  282. // Retrieve all observed descriptors
  283. vector<cv::Mat> vDescriptors;
  284. map<KeyFrame*,tuple<int,int>> observations;
  285. {
  286. unique_lock<mutex> lock1(mMutexFeatures);
  287. if(mbBad)
  288. return;
  289. observations=mObservations;
  290. }
  291. if(observations.empty())
  292. return;
  293. vDescriptors.reserve(observations.size());
  294. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  295. {
  296. KeyFrame* pKF = mit->first;
  297. if(!pKF->isBad()){
  298. tuple<int,int> indexes = mit -> second;
  299. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  300. if(leftIndex != -1){
  301. vDescriptors.push_back(pKF->mDescriptors.row(leftIndex));
  302. }
  303. if(rightIndex != -1){
  304. vDescriptors.push_back(pKF->mDescriptors.row(rightIndex));
  305. }
  306. }
  307. }
  308. if(vDescriptors.empty())
  309. return;
  310. // Compute distances between them
  311. const size_t N = vDescriptors.size();
  312. float Distances[N][N];
  313. for(size_t i=0;i<N;i++)
  314. {
  315. Distances[i][i]=0;
  316. for(size_t j=i+1;j<N;j++)
  317. {
  318. int distij = ORBmatcher::DescriptorDistance(vDescriptors[i],vDescriptors[j]);
  319. Distances[i][j]=distij;
  320. Distances[j][i]=distij;
  321. }
  322. }
  323. // Take the descriptor with least median distance to the rest
  324. int BestMedian = INT_MAX;
  325. int BestIdx = 0;
  326. for(size_t i=0;i<N;i++)
  327. {
  328. vector<int> vDists(Distances[i],Distances[i]+N);
  329. sort(vDists.begin(),vDists.end());
  330. int median = vDists[0.5*(N-1)];
  331. if(median<BestMedian)
  332. {
  333. BestMedian = median;
  334. BestIdx = i;
  335. }
  336. }
  337. {
  338. unique_lock<mutex> lock(mMutexFeatures);
  339. mDescriptor = vDescriptors[BestIdx].clone();
  340. }
  341. }
  342. cv::Mat MapPoint::GetDescriptor()
  343. {
  344. unique_lock<mutex> lock(mMutexFeatures);
  345. return mDescriptor.clone();
  346. }
  347. tuple<int,int> MapPoint::GetIndexInKeyFrame(KeyFrame *pKF)
  348. {
  349. unique_lock<mutex> lock(mMutexFeatures);
  350. if(mObservations.count(pKF))
  351. return mObservations[pKF];
  352. else
  353. return tuple<int,int>(-1,-1);
  354. }
  355. bool MapPoint::IsInKeyFrame(KeyFrame *pKF)
  356. {
  357. unique_lock<mutex> lock(mMutexFeatures);
  358. return (mObservations.count(pKF));
  359. }
  360. void MapPoint::UpdateNormalAndDepth()
  361. {
  362. map<KeyFrame*,tuple<int,int>> observations;
  363. KeyFrame* pRefKF;
  364. cv::Mat Pos;
  365. {
  366. unique_lock<mutex> lock1(mMutexFeatures);
  367. unique_lock<mutex> lock2(mMutexPos);
  368. if(mbBad)
  369. return;
  370. observations=mObservations;
  371. pRefKF=mpRefKF;
  372. Pos = mWorldPos.clone();
  373. }
  374. if(observations.empty())
  375. return;
  376. cv::Mat normal = cv::Mat::zeros(3,1,CV_32F);
  377. int n=0;
  378. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  379. {
  380. KeyFrame* pKF = mit->first;
  381. tuple<int,int> indexes = mit -> second;
  382. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  383. if(leftIndex != -1){
  384. cv::Mat Owi = pKF->GetCameraCenter();
  385. cv::Mat normali = mWorldPos - Owi;
  386. normal = normal + normali/cv::norm(normali);
  387. n++;
  388. }
  389. if(rightIndex != -1){
  390. cv::Mat Owi = pKF->GetRightCameraCenter();
  391. cv::Mat normali = mWorldPos - Owi;
  392. normal = normal + normali/cv::norm(normali);
  393. n++;
  394. }
  395. }
  396. cv::Mat PC = Pos - pRefKF->GetCameraCenter();
  397. const float dist = cv::norm(PC);
  398. tuple<int ,int> indexes = observations[pRefKF];
  399. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  400. int level;
  401. if(pRefKF -> NLeft == -1){
  402. level = pRefKF->mvKeysUn[leftIndex].octave;
  403. }
  404. else if(leftIndex != -1){
  405. level = pRefKF -> mvKeys[leftIndex].octave;
  406. }
  407. else{
  408. level = pRefKF -> mvKeysRight[rightIndex - pRefKF -> NLeft].octave;
  409. }
  410. //const int level = pRefKF->mvKeysUn[observations[pRefKF]].octave;
  411. const float levelScaleFactor = pRefKF->mvScaleFactors[level];
  412. const int nLevels = pRefKF->mnScaleLevels;
  413. {
  414. unique_lock<mutex> lock3(mMutexPos);
  415. mfMaxDistance = dist*levelScaleFactor;
  416. mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1];
  417. mNormalVector = normal/n;
  418. }
  419. }
  420. void MapPoint::SetNormalVector(cv::Mat& normal)
  421. {
  422. unique_lock<mutex> lock3(mMutexPos);
  423. mNormalVector = normal;
  424. }
  425. float MapPoint::GetMinDistanceInvariance()
  426. {
  427. unique_lock<mutex> lock(mMutexPos);
  428. return 0.8f*mfMinDistance;
  429. }
  430. float MapPoint::GetMaxDistanceInvariance()
  431. {
  432. unique_lock<mutex> lock(mMutexPos);
  433. return 1.2f*mfMaxDistance;
  434. }
  435. int MapPoint::PredictScale(const float &currentDist, KeyFrame* pKF)
  436. {
  437. float ratio;
  438. {
  439. unique_lock<mutex> lock(mMutexPos);
  440. ratio = mfMaxDistance/currentDist;
  441. }
  442. int nScale = ceil(log(ratio)/pKF->mfLogScaleFactor);
  443. if(nScale<0)
  444. nScale = 0;
  445. else if(nScale>=pKF->mnScaleLevels)
  446. nScale = pKF->mnScaleLevels-1;
  447. return nScale;
  448. }
  449. int MapPoint::PredictScale(const float &currentDist, Frame* pF)
  450. {
  451. float ratio;
  452. {
  453. unique_lock<mutex> lock(mMutexPos);
  454. ratio = mfMaxDistance/currentDist;
  455. }
  456. int nScale = ceil(log(ratio)/pF->mfLogScaleFactor);
  457. if(nScale<0)
  458. nScale = 0;
  459. else if(nScale>=pF->mnScaleLevels)
  460. nScale = pF->mnScaleLevels-1;
  461. return nScale;
  462. }
  463. void MapPoint::PrintObservations()
  464. {
  465. cout << "MP_OBS: MP " << mnId << endl;
  466. for(map<KeyFrame*,tuple<int,int>>::iterator mit=mObservations.begin(), mend=mObservations.end(); mit!=mend; mit++)
  467. {
  468. KeyFrame* pKFi = mit->first;
  469. tuple<int,int> indexes = mit->second;
  470. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  471. cout << "--OBS in KF " << pKFi->mnId << " in map " << pKFi->GetMap()->GetId() << endl;
  472. }
  473. }
  474. Map* MapPoint::GetMap()
  475. {
  476. unique_lock<mutex> lock(mMutexMap);
  477. return mpMap;
  478. }
  479. void MapPoint::UpdateMap(Map* pMap)
  480. {
  481. unique_lock<mutex> lock(mMutexMap);
  482. mpMap = pMap;
  483. }
  484. void MapPoint::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP)
  485. {
  486. mBackupReplacedId = -1;
  487. if(mpReplaced && spMP.find(mpReplaced) != spMP.end())
  488. mBackupReplacedId = mpReplaced->mnId;
  489. mBackupObservationsId1.clear();
  490. mBackupObservationsId2.clear();
  491. // Save the id and position in each KF who view it
  492. for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(), end = mObservations.end(); it != end; ++it)
  493. {
  494. KeyFrame* pKFi = it->first;
  495. if(spKF.find(pKFi) != spKF.end())
  496. {
  497. mBackupObservationsId1[it->first->mnId] = get<0>(it->second);
  498. mBackupObservationsId2[it->first->mnId] = get<1>(it->second);
  499. }
  500. else
  501. {
  502. EraseObservation(pKFi);
  503. }
  504. }
  505. // Save the id of the reference KF
  506. if(spKF.find(mpRefKF) != spKF.end())
  507. {
  508. mBackupRefKFId = mpRefKF->mnId;
  509. }
  510. }
  511. void MapPoint::PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid)
  512. {
  513. mpRefKF = mpKFid[mBackupRefKFId];
  514. if(!mpRefKF)
  515. {
  516. cout << "MP without KF reference " << mBackupRefKFId << "; Num obs: " << nObs << endl;
  517. }
  518. mpReplaced = static_cast<MapPoint*>(NULL);
  519. if(mBackupReplacedId>=0)
  520. {
  521. map<long unsigned int, MapPoint*>::iterator it = mpMPid.find(mBackupReplacedId);
  522. if (it != mpMPid.end())
  523. mpReplaced = it->second;
  524. }
  525. mObservations.clear();
  526. for(map<long unsigned int, int>::const_iterator it = mBackupObservationsId1.begin(), end = mBackupObservationsId1.end(); it != end; ++it)
  527. {
  528. KeyFrame* pKFi = mpKFid[it->first];
  529. map<long unsigned int, int>::const_iterator it2 = mBackupObservationsId2.find(it->first);
  530. std::tuple<int, int> indexes = tuple<int,int>(it->second,it2->second);
  531. if(pKFi)
  532. {
  533. mObservations[pKFi] = indexes;
  534. }
  535. }
  536. mBackupObservationsId1.clear();
  537. mBackupObservationsId2.clear();
  538. }
  539. } //namespace ORB_SLAM