MapPoint.cc 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634
  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 "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 Eigen::Vector3f &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. SetWorldPos(Pos);
  41. mNormalVector.setZero();
  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.setZero();
  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 Eigen::Vector3f &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. SetWorldPos(Pos);
  72. Eigen::Vector3f Ow;
  73. if(pFrame -> Nleft == -1 || idxF < pFrame -> Nleft){
  74. Ow = pFrame->GetCameraCenter();
  75. }
  76. else{
  77. Eigen::Matrix3f Rwl = pFrame->GetRwc();
  78. Eigen::Vector3f tlr = pFrame->GetRelativePoseTlr().translation();
  79. Eigen::Vector3f twl = pFrame->GetOw();
  80. Ow = Rwl * tlr + twl;
  81. }
  82. mNormalVector = mWorldPos - Ow;
  83. mNormalVector = mNormalVector / mNormalVector.norm();
  84. Eigen::Vector3f PC = mWorldPos - Ow;
  85. const float dist = PC.norm();
  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 Eigen::Vector3f &Pos) {
  99. unique_lock<mutex> lock2(mGlobalMutex);
  100. unique_lock<mutex> lock(mMutexPos);
  101. mWorldPos = Pos;
  102. }
  103. Eigen::Vector3f MapPoint::GetWorldPos() {
  104. unique_lock<mutex> lock(mMutexPos);
  105. return mWorldPos;
  106. }
  107. Eigen::Vector3f MapPoint::GetNormal() {
  108. unique_lock<mutex> lock(mMutexPos);
  109. return mNormalVector;
  110. }
  111. KeyFrame* MapPoint::GetReferenceKeyFrame()
  112. {
  113. unique_lock<mutex> lock(mMutexFeatures);
  114. return mpRefKF;
  115. }
  116. void MapPoint::AddObservation(KeyFrame* pKF, int idx)
  117. {
  118. unique_lock<mutex> lock(mMutexFeatures);
  119. tuple<int,int> indexes;
  120. if(mObservations.count(pKF)){
  121. indexes = mObservations[pKF];
  122. }
  123. else{
  124. indexes = tuple<int,int>(-1,-1);
  125. }
  126. if(pKF -> NLeft != -1 && idx >= pKF -> NLeft){
  127. get<1>(indexes) = idx;
  128. }
  129. else{
  130. get<0>(indexes) = idx;
  131. }
  132. mObservations[pKF]=indexes;
  133. if(!pKF->mpCamera2 && pKF->mvuRight[idx]>=0)
  134. nObs+=2;
  135. else
  136. nObs++;
  137. }
  138. void MapPoint::EraseObservation(KeyFrame* pKF)
  139. {
  140. bool bBad=false;
  141. {
  142. unique_lock<mutex> lock(mMutexFeatures);
  143. if(mObservations.count(pKF))
  144. {
  145. tuple<int,int> indexes = mObservations[pKF];
  146. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  147. if(leftIndex != -1){
  148. if(!pKF->mpCamera2 && pKF->mvuRight[leftIndex]>=0)
  149. nObs-=2;
  150. else
  151. nObs--;
  152. }
  153. if(rightIndex != -1){
  154. nObs--;
  155. }
  156. mObservations.erase(pKF);
  157. if(mpRefKF==pKF)
  158. mpRefKF=mObservations.begin()->first;
  159. // If only 2 observations or less, discard point
  160. if(nObs<=2)
  161. bBad=true;
  162. }
  163. }
  164. if(bBad)
  165. SetBadFlag();
  166. }
  167. std::map<KeyFrame*, std::tuple<int,int>> MapPoint::GetObservations()
  168. {
  169. unique_lock<mutex> lock(mMutexFeatures);
  170. return mObservations;
  171. }
  172. int MapPoint::Observations()
  173. {
  174. unique_lock<mutex> lock(mMutexFeatures);
  175. return nObs;
  176. }
  177. void MapPoint::SetBadFlag()
  178. {
  179. map<KeyFrame*, tuple<int,int>> obs;
  180. {
  181. unique_lock<mutex> lock1(mMutexFeatures);
  182. unique_lock<mutex> lock2(mMutexPos);
  183. mbBad=true;
  184. obs = mObservations;
  185. mObservations.clear();
  186. }
  187. for(map<KeyFrame*, tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  188. {
  189. KeyFrame* pKF = mit->first;
  190. int leftIndex = get<0>(mit -> second), rightIndex = get<1>(mit -> second);
  191. if(leftIndex != -1){
  192. pKF->EraseMapPointMatch(leftIndex);
  193. }
  194. if(rightIndex != -1){
  195. pKF->EraseMapPointMatch(rightIndex);
  196. }
  197. }
  198. mpMap->EraseMapPoint(this);
  199. }
  200. MapPoint* MapPoint::GetReplaced()
  201. {
  202. unique_lock<mutex> lock1(mMutexFeatures);
  203. unique_lock<mutex> lock2(mMutexPos);
  204. return mpReplaced;
  205. }
  206. void MapPoint::Replace(MapPoint* pMP)
  207. {
  208. if(pMP->mnId==this->mnId)
  209. return;
  210. int nvisible, nfound;
  211. map<KeyFrame*,tuple<int,int>> obs;
  212. {
  213. unique_lock<mutex> lock1(mMutexFeatures);
  214. unique_lock<mutex> lock2(mMutexPos);
  215. obs=mObservations;
  216. mObservations.clear();
  217. mbBad=true;
  218. nvisible = mnVisible;
  219. nfound = mnFound;
  220. mpReplaced = pMP;
  221. }
  222. for(map<KeyFrame*,tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  223. {
  224. // Replace measurement in keyframe
  225. KeyFrame* pKF = mit->first;
  226. tuple<int,int> indexes = mit -> second;
  227. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  228. if(!pMP->IsInKeyFrame(pKF))
  229. {
  230. if(leftIndex != -1){
  231. pKF->ReplaceMapPointMatch(leftIndex, pMP);
  232. pMP->AddObservation(pKF,leftIndex);
  233. }
  234. if(rightIndex != -1){
  235. pKF->ReplaceMapPointMatch(rightIndex, pMP);
  236. pMP->AddObservation(pKF,rightIndex);
  237. }
  238. }
  239. else
  240. {
  241. if(leftIndex != -1){
  242. pKF->EraseMapPointMatch(leftIndex);
  243. }
  244. if(rightIndex != -1){
  245. pKF->EraseMapPointMatch(rightIndex);
  246. }
  247. }
  248. }
  249. pMP->IncreaseFound(nfound);
  250. pMP->IncreaseVisible(nvisible);
  251. pMP->ComputeDistinctiveDescriptors();
  252. mpMap->EraseMapPoint(this);
  253. }
  254. bool MapPoint::isBad()
  255. {
  256. unique_lock<mutex> lock1(mMutexFeatures,std::defer_lock);
  257. unique_lock<mutex> lock2(mMutexPos,std::defer_lock);
  258. lock(lock1, lock2);
  259. return mbBad;
  260. }
  261. void MapPoint::IncreaseVisible(int n)
  262. {
  263. unique_lock<mutex> lock(mMutexFeatures);
  264. mnVisible+=n;
  265. }
  266. void MapPoint::IncreaseFound(int n)
  267. {
  268. unique_lock<mutex> lock(mMutexFeatures);
  269. mnFound+=n;
  270. }
  271. float MapPoint::GetFoundRatio()
  272. {
  273. unique_lock<mutex> lock(mMutexFeatures);
  274. return static_cast<float>(mnFound)/mnVisible;
  275. }
  276. void MapPoint::ComputeDistinctiveDescriptors()
  277. {
  278. // Retrieve all observed descriptors
  279. vector<cv::Mat> vDescriptors;
  280. map<KeyFrame*,tuple<int,int>> observations;
  281. {
  282. unique_lock<mutex> lock1(mMutexFeatures);
  283. if(mbBad)
  284. return;
  285. observations=mObservations;
  286. }
  287. if(observations.empty())
  288. return;
  289. vDescriptors.reserve(observations.size());
  290. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  291. {
  292. KeyFrame* pKF = mit->first;
  293. if(!pKF->isBad()){
  294. tuple<int,int> indexes = mit -> second;
  295. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  296. if(leftIndex != -1){
  297. vDescriptors.push_back(pKF->mDescriptors.row(leftIndex));
  298. }
  299. if(rightIndex != -1){
  300. vDescriptors.push_back(pKF->mDescriptors.row(rightIndex));
  301. }
  302. }
  303. }
  304. if(vDescriptors.empty())
  305. return;
  306. // Compute distances between them
  307. const size_t N = vDescriptors.size();
  308. float Distances[N][N];
  309. for(size_t i=0;i<N;i++)
  310. {
  311. Distances[i][i]=0;
  312. for(size_t j=i+1;j<N;j++)
  313. {
  314. int distij = ORBmatcher::DescriptorDistance(vDescriptors[i],vDescriptors[j]);
  315. Distances[i][j]=distij;
  316. Distances[j][i]=distij;
  317. }
  318. }
  319. // Take the descriptor with least median distance to the rest
  320. int BestMedian = INT_MAX;
  321. int BestIdx = 0;
  322. for(size_t i=0;i<N;i++)
  323. {
  324. vector<int> vDists(Distances[i],Distances[i]+N);
  325. sort(vDists.begin(),vDists.end());
  326. int median = vDists[0.5*(N-1)];
  327. if(median<BestMedian)
  328. {
  329. BestMedian = median;
  330. BestIdx = i;
  331. }
  332. }
  333. {
  334. unique_lock<mutex> lock(mMutexFeatures);
  335. mDescriptor = vDescriptors[BestIdx].clone();
  336. }
  337. }
  338. cv::Mat MapPoint::GetDescriptor()
  339. {
  340. unique_lock<mutex> lock(mMutexFeatures);
  341. return mDescriptor.clone();
  342. }
  343. tuple<int,int> MapPoint::GetIndexInKeyFrame(KeyFrame *pKF)
  344. {
  345. unique_lock<mutex> lock(mMutexFeatures);
  346. if(mObservations.count(pKF))
  347. return mObservations[pKF];
  348. else
  349. return tuple<int,int>(-1,-1);
  350. }
  351. bool MapPoint::IsInKeyFrame(KeyFrame *pKF)
  352. {
  353. unique_lock<mutex> lock(mMutexFeatures);
  354. return (mObservations.count(pKF));
  355. }
  356. void MapPoint::UpdateNormalAndDepth()
  357. {
  358. map<KeyFrame*,tuple<int,int>> observations;
  359. KeyFrame* pRefKF;
  360. Eigen::Vector3f Pos;
  361. {
  362. unique_lock<mutex> lock1(mMutexFeatures);
  363. unique_lock<mutex> lock2(mMutexPos);
  364. if(mbBad)
  365. return;
  366. observations = mObservations;
  367. pRefKF = mpRefKF;
  368. Pos = mWorldPos;
  369. }
  370. if(observations.empty())
  371. return;
  372. Eigen::Vector3f normal;
  373. normal.setZero();
  374. int n=0;
  375. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  376. {
  377. KeyFrame* pKF = mit->first;
  378. tuple<int,int> indexes = mit -> second;
  379. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  380. if(leftIndex != -1){
  381. Eigen::Vector3f Owi = pKF->GetCameraCenter();
  382. Eigen::Vector3f normali = Pos - Owi;
  383. normal = normal + normali / normali.norm();
  384. n++;
  385. }
  386. if(rightIndex != -1){
  387. Eigen::Vector3f Owi = pKF->GetRightCameraCenter();
  388. Eigen::Vector3f normali = Pos - Owi;
  389. normal = normal + normali / normali.norm();
  390. n++;
  391. }
  392. }
  393. Eigen::Vector3f PC = Pos - pRefKF->GetCameraCenter();
  394. const float dist = PC.norm();
  395. tuple<int ,int> indexes = observations[pRefKF];
  396. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  397. int level;
  398. if(pRefKF -> NLeft == -1){
  399. level = pRefKF->mvKeysUn[leftIndex].octave;
  400. }
  401. else if(leftIndex != -1){
  402. level = pRefKF -> mvKeys[leftIndex].octave;
  403. }
  404. else{
  405. level = pRefKF -> mvKeysRight[rightIndex - pRefKF -> NLeft].octave;
  406. }
  407. //const int level = pRefKF->mvKeysUn[observations[pRefKF]].octave;
  408. const float levelScaleFactor = pRefKF->mvScaleFactors[level];
  409. const int nLevels = pRefKF->mnScaleLevels;
  410. {
  411. unique_lock<mutex> lock3(mMutexPos);
  412. mfMaxDistance = dist*levelScaleFactor;
  413. mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1];
  414. mNormalVector = normal/n;
  415. }
  416. }
  417. void MapPoint::SetNormalVector(const Eigen::Vector3f& normal)
  418. {
  419. unique_lock<mutex> lock3(mMutexPos);
  420. mNormalVector = normal;
  421. }
  422. float MapPoint::GetMinDistanceInvariance()
  423. {
  424. unique_lock<mutex> lock(mMutexPos);
  425. return 0.8f * mfMinDistance;
  426. }
  427. float MapPoint::GetMaxDistanceInvariance()
  428. {
  429. unique_lock<mutex> lock(mMutexPos);
  430. return 1.2f * mfMaxDistance;
  431. }
  432. int MapPoint::PredictScale(const float &currentDist, KeyFrame* pKF)
  433. {
  434. float ratio;
  435. {
  436. unique_lock<mutex> lock(mMutexPos);
  437. ratio = mfMaxDistance/currentDist;
  438. }
  439. int nScale = ceil(log(ratio)/pKF->mfLogScaleFactor);
  440. if(nScale<0)
  441. nScale = 0;
  442. else if(nScale>=pKF->mnScaleLevels)
  443. nScale = pKF->mnScaleLevels-1;
  444. return nScale;
  445. }
  446. int MapPoint::PredictScale(const float &currentDist, Frame* pF)
  447. {
  448. float ratio;
  449. {
  450. unique_lock<mutex> lock(mMutexPos);
  451. ratio = mfMaxDistance/currentDist;
  452. }
  453. int nScale = ceil(log(ratio)/pF->mfLogScaleFactor);
  454. if(nScale<0)
  455. nScale = 0;
  456. else if(nScale>=pF->mnScaleLevels)
  457. nScale = pF->mnScaleLevels-1;
  458. return nScale;
  459. }
  460. void MapPoint::PrintObservations()
  461. {
  462. cout << "MP_OBS: MP " << mnId << endl;
  463. for(map<KeyFrame*,tuple<int,int>>::iterator mit=mObservations.begin(), mend=mObservations.end(); mit!=mend; mit++)
  464. {
  465. KeyFrame* pKFi = mit->first;
  466. tuple<int,int> indexes = mit->second;
  467. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  468. cout << "--OBS in KF " << pKFi->mnId << " in map " << pKFi->GetMap()->GetId() << endl;
  469. }
  470. }
  471. Map* MapPoint::GetMap()
  472. {
  473. unique_lock<mutex> lock(mMutexMap);
  474. return mpMap;
  475. }
  476. void MapPoint::UpdateMap(Map* pMap)
  477. {
  478. unique_lock<mutex> lock(mMutexMap);
  479. mpMap = pMap;
  480. }
  481. void MapPoint::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP)
  482. {
  483. mBackupReplacedId = -1;
  484. if(mpReplaced && spMP.find(mpReplaced) != spMP.end())
  485. mBackupReplacedId = mpReplaced->mnId;
  486. mBackupObservationsId1.clear();
  487. mBackupObservationsId2.clear();
  488. // Save the id and position in each KF who view it
  489. for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(), end = mObservations.end(); it != end; ++it)
  490. {
  491. KeyFrame* pKFi = it->first;
  492. if(spKF.find(pKFi) != spKF.end())
  493. {
  494. mBackupObservationsId1[it->first->mnId] = get<0>(it->second);
  495. mBackupObservationsId2[it->first->mnId] = get<1>(it->second);
  496. }
  497. else
  498. {
  499. EraseObservation(pKFi);
  500. }
  501. }
  502. // Save the id of the reference KF
  503. if(spKF.find(mpRefKF) != spKF.end())
  504. {
  505. mBackupRefKFId = mpRefKF->mnId;
  506. }
  507. }
  508. void MapPoint::PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid)
  509. {
  510. mpRefKF = mpKFid[mBackupRefKFId];
  511. if(!mpRefKF)
  512. {
  513. cout << "ERROR: MP without KF reference " << mBackupRefKFId << "; Num obs: " << nObs << endl;
  514. }
  515. mpReplaced = static_cast<MapPoint*>(NULL);
  516. if(mBackupReplacedId>=0)
  517. {
  518. map<long unsigned int, MapPoint*>::iterator it = mpMPid.find(mBackupReplacedId);
  519. if (it != mpMPid.end())
  520. mpReplaced = it->second;
  521. }
  522. mObservations.clear();
  523. for(map<long unsigned int, int>::const_iterator it = mBackupObservationsId1.begin(), end = mBackupObservationsId1.end(); it != end; ++it)
  524. {
  525. KeyFrame* pKFi = mpKFid[it->first];
  526. map<long unsigned int, int>::const_iterator it2 = mBackupObservationsId2.find(it->first);
  527. std::tuple<int, int> indexes = tuple<int,int>(it->second,it2->second);
  528. if(pKFi)
  529. {
  530. mObservations[pKFi] = indexes;
  531. }
  532. }
  533. mBackupObservationsId1.clear();
  534. mBackupObservationsId2.clear();
  535. }
  536. } //namespace ORB_SLAM