MapPoint.cc 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580
  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. mWorldPosx = cv::Matx31f(Pos.at<float>(0), Pos.at<float>(1), Pos.at<float>(2));
  42. mNormalVector = cv::Mat::zeros(3,1,CV_32F);
  43. mNormalVectorx = cv::Matx31f::zeros();
  44. mbTrackInViewR = false;
  45. mbTrackInView = false;
  46. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  47. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  48. mnId=nNextId++;
  49. }
  50. MapPoint::MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap):
  51. mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0),
  52. mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0),
  53. mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false),
  54. mpReplaced(static_cast<MapPoint*>(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap),
  55. mnOriginMapId(pMap->GetId())
  56. {
  57. mInvDepth=invDepth;
  58. mInitU=(double)uv_init.x;
  59. mInitV=(double)uv_init.y;
  60. mpHostKF = pHostKF;
  61. mNormalVector = cv::Mat::zeros(3,1,CV_32F);
  62. mNormalVectorx = cv::Matx31f::zeros();
  63. // Worldpos is not set
  64. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  65. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  66. mnId=nNextId++;
  67. }
  68. MapPoint::MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF):
  69. mnFirstKFid(-1), mnFirstFrame(pFrame->mnId), nObs(0), mnTrackReferenceForFrame(0), mnLastFrameSeen(0),
  70. mnBALocalForKF(0), mnFuseCandidateForKF(0),mnLoopPointForKF(0), mnCorrectedByKF(0),
  71. mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(static_cast<KeyFrame*>(NULL)), mnVisible(1),
  72. mnFound(1), mbBad(false), mpReplaced(NULL), mpMap(pMap), mnOriginMapId(pMap->GetId())
  73. {
  74. Pos.copyTo(mWorldPos);
  75. mWorldPosx = cv::Matx31f(Pos.at<float>(0), Pos.at<float>(1), Pos.at<float>(2));
  76. cv::Mat Ow;
  77. if(pFrame -> Nleft == -1 || idxF < pFrame -> Nleft){
  78. Ow = pFrame->GetCameraCenter();
  79. }
  80. else{
  81. cv::Mat Rwl = pFrame -> mRwc;
  82. cv::Mat tlr = pFrame -> mTlr.col(3);
  83. cv::Mat twl = pFrame -> mOw;
  84. Ow = Rwl * tlr + twl;
  85. }
  86. mNormalVector = mWorldPos - Ow;
  87. mNormalVector = mNormalVector/cv::norm(mNormalVector);
  88. mNormalVectorx = cv::Matx31f(mNormalVector.at<float>(0), mNormalVector.at<float>(1), mNormalVector.at<float>(2));
  89. cv::Mat PC = Pos - Ow;
  90. const float dist = cv::norm(PC);
  91. const int level = (pFrame -> Nleft == -1) ? pFrame->mvKeysUn[idxF].octave
  92. : (idxF < pFrame -> Nleft) ? pFrame->mvKeys[idxF].octave
  93. : pFrame -> mvKeysRight[idxF].octave;
  94. const float levelScaleFactor = pFrame->mvScaleFactors[level];
  95. const int nLevels = pFrame->mnScaleLevels;
  96. mfMaxDistance = dist*levelScaleFactor;
  97. mfMinDistance = mfMaxDistance/pFrame->mvScaleFactors[nLevels-1];
  98. pFrame->mDescriptors.row(idxF).copyTo(mDescriptor);
  99. // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
  100. unique_lock<mutex> lock(mpMap->mMutexPointCreation);
  101. mnId=nNextId++;
  102. }
  103. void MapPoint::SetWorldPos(const cv::Mat &Pos)
  104. {
  105. unique_lock<mutex> lock2(mGlobalMutex);
  106. unique_lock<mutex> lock(mMutexPos);
  107. Pos.copyTo(mWorldPos);
  108. mWorldPosx = cv::Matx31f(Pos.at<float>(0), Pos.at<float>(1), Pos.at<float>(2));
  109. }
  110. cv::Mat MapPoint::GetWorldPos()
  111. {
  112. unique_lock<mutex> lock(mMutexPos);
  113. return mWorldPos.clone();
  114. }
  115. cv::Mat MapPoint::GetNormal()
  116. {
  117. unique_lock<mutex> lock(mMutexPos);
  118. return mNormalVector.clone();
  119. }
  120. cv::Matx31f MapPoint::GetWorldPos2()
  121. {
  122. unique_lock<mutex> lock(mMutexPos);
  123. return mWorldPosx;
  124. }
  125. cv::Matx31f MapPoint::GetNormal2()
  126. {
  127. unique_lock<mutex> lock(mMutexPos);
  128. return mNormalVectorx;
  129. }
  130. KeyFrame* MapPoint::GetReferenceKeyFrame()
  131. {
  132. unique_lock<mutex> lock(mMutexFeatures);
  133. return mpRefKF;
  134. }
  135. void MapPoint::AddObservation(KeyFrame* pKF, int idx)
  136. {
  137. unique_lock<mutex> lock(mMutexFeatures);
  138. tuple<int,int> indexes;
  139. if(mObservations.count(pKF)){
  140. indexes = mObservations[pKF];
  141. }
  142. else{
  143. indexes = tuple<int,int>(-1,-1);
  144. }
  145. if(pKF -> NLeft != -1 && idx >= pKF -> NLeft){
  146. get<1>(indexes) = idx;
  147. }
  148. else{
  149. get<0>(indexes) = idx;
  150. }
  151. mObservations[pKF]=indexes;
  152. if(!pKF->mpCamera2 && pKF->mvuRight[idx]>=0)
  153. nObs+=2;
  154. else
  155. nObs++;
  156. }
  157. void MapPoint::EraseObservation(KeyFrame* pKF)
  158. {
  159. bool bBad=false;
  160. {
  161. unique_lock<mutex> lock(mMutexFeatures);
  162. if(mObservations.count(pKF))
  163. {
  164. tuple<int,int> indexes = mObservations[pKF];
  165. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  166. if(leftIndex != -1){
  167. if(!pKF->mpCamera2 && pKF->mvuRight[leftIndex]>=0)
  168. nObs-=2;
  169. else
  170. nObs--;
  171. }
  172. if(rightIndex != -1){
  173. nObs--;
  174. }
  175. mObservations.erase(pKF);
  176. if(mpRefKF==pKF)
  177. mpRefKF=mObservations.begin()->first;
  178. // If only 2 observations or less, discard point
  179. if(nObs<=2)
  180. bBad=true;
  181. }
  182. }
  183. if(bBad)
  184. SetBadFlag();
  185. }
  186. std::map<KeyFrame*, std::tuple<int,int>> MapPoint::GetObservations()
  187. {
  188. unique_lock<mutex> lock(mMutexFeatures);
  189. return mObservations;
  190. }
  191. int MapPoint::Observations()
  192. {
  193. unique_lock<mutex> lock(mMutexFeatures);
  194. return nObs;
  195. }
  196. void MapPoint::SetBadFlag()
  197. {
  198. map<KeyFrame*, tuple<int,int>> obs;
  199. {
  200. unique_lock<mutex> lock1(mMutexFeatures);
  201. unique_lock<mutex> lock2(mMutexPos);
  202. mbBad=true;
  203. obs = mObservations;
  204. mObservations.clear();
  205. }
  206. for(map<KeyFrame*, tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  207. {
  208. KeyFrame* pKF = mit->first;
  209. int leftIndex = get<0>(mit -> second), rightIndex = get<1>(mit -> second);
  210. if(leftIndex != -1){
  211. pKF->EraseMapPointMatch(leftIndex);
  212. }
  213. if(rightIndex != -1){
  214. pKF->EraseMapPointMatch(rightIndex);
  215. }
  216. }
  217. mpMap->EraseMapPoint(this);
  218. }
  219. MapPoint* MapPoint::GetReplaced()
  220. {
  221. unique_lock<mutex> lock1(mMutexFeatures);
  222. unique_lock<mutex> lock2(mMutexPos);
  223. return mpReplaced;
  224. }
  225. void MapPoint::Replace(MapPoint* pMP)
  226. {
  227. if(pMP->mnId==this->mnId)
  228. return;
  229. int nvisible, nfound;
  230. map<KeyFrame*,tuple<int,int>> obs;
  231. {
  232. unique_lock<mutex> lock1(mMutexFeatures);
  233. unique_lock<mutex> lock2(mMutexPos);
  234. obs=mObservations;
  235. mObservations.clear();
  236. mbBad=true;
  237. nvisible = mnVisible;
  238. nfound = mnFound;
  239. mpReplaced = pMP;
  240. }
  241. for(map<KeyFrame*,tuple<int,int>>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
  242. {
  243. // Replace measurement in keyframe
  244. KeyFrame* pKF = mit->first;
  245. tuple<int,int> indexes = mit -> second;
  246. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  247. if(!pMP->IsInKeyFrame(pKF))
  248. {
  249. if(leftIndex != -1){
  250. pKF->ReplaceMapPointMatch(leftIndex, pMP);
  251. pMP->AddObservation(pKF,leftIndex);
  252. }
  253. if(rightIndex != -1){
  254. pKF->ReplaceMapPointMatch(rightIndex, pMP);
  255. pMP->AddObservation(pKF,rightIndex);
  256. }
  257. }
  258. else
  259. {
  260. if(leftIndex != -1){
  261. pKF->EraseMapPointMatch(leftIndex);
  262. }
  263. if(rightIndex != -1){
  264. pKF->EraseMapPointMatch(rightIndex);
  265. }
  266. }
  267. }
  268. pMP->IncreaseFound(nfound);
  269. pMP->IncreaseVisible(nvisible);
  270. pMP->ComputeDistinctiveDescriptors();
  271. mpMap->EraseMapPoint(this);
  272. }
  273. bool MapPoint::isBad()
  274. {
  275. unique_lock<mutex> lock1(mMutexFeatures,std::defer_lock);
  276. unique_lock<mutex> lock2(mMutexPos,std::defer_lock);
  277. lock(lock1, lock2);
  278. return mbBad;
  279. }
  280. void MapPoint::IncreaseVisible(int n)
  281. {
  282. unique_lock<mutex> lock(mMutexFeatures);
  283. mnVisible+=n;
  284. }
  285. void MapPoint::IncreaseFound(int n)
  286. {
  287. unique_lock<mutex> lock(mMutexFeatures);
  288. mnFound+=n;
  289. }
  290. float MapPoint::GetFoundRatio()
  291. {
  292. unique_lock<mutex> lock(mMutexFeatures);
  293. return static_cast<float>(mnFound)/mnVisible;
  294. }
  295. void MapPoint::ComputeDistinctiveDescriptors()
  296. {
  297. // Retrieve all observed descriptors
  298. vector<cv::Mat> vDescriptors;
  299. map<KeyFrame*,tuple<int,int>> observations;
  300. {
  301. unique_lock<mutex> lock1(mMutexFeatures);
  302. if(mbBad)
  303. return;
  304. observations=mObservations;
  305. }
  306. if(observations.empty())
  307. return;
  308. vDescriptors.reserve(observations.size());
  309. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  310. {
  311. KeyFrame* pKF = mit->first;
  312. if(!pKF->isBad()){
  313. tuple<int,int> indexes = mit -> second;
  314. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  315. if(leftIndex != -1){
  316. vDescriptors.push_back(pKF->mDescriptors.row(leftIndex));
  317. }
  318. if(rightIndex != -1){
  319. vDescriptors.push_back(pKF->mDescriptors.row(rightIndex));
  320. }
  321. }
  322. }
  323. if(vDescriptors.empty())
  324. return;
  325. // Compute distances between them
  326. const size_t N = vDescriptors.size();
  327. float Distances[N][N];
  328. for(size_t i=0;i<N;i++)
  329. {
  330. Distances[i][i]=0;
  331. for(size_t j=i+1;j<N;j++)
  332. {
  333. int distij = ORBmatcher::DescriptorDistance(vDescriptors[i],vDescriptors[j]);
  334. Distances[i][j]=distij;
  335. Distances[j][i]=distij;
  336. }
  337. }
  338. // Take the descriptor with least median distance to the rest
  339. int BestMedian = INT_MAX;
  340. int BestIdx = 0;
  341. for(size_t i=0;i<N;i++)
  342. {
  343. vector<int> vDists(Distances[i],Distances[i]+N);
  344. sort(vDists.begin(),vDists.end());
  345. int median = vDists[0.5*(N-1)];
  346. if(median<BestMedian)
  347. {
  348. BestMedian = median;
  349. BestIdx = i;
  350. }
  351. }
  352. {
  353. unique_lock<mutex> lock(mMutexFeatures);
  354. mDescriptor = vDescriptors[BestIdx].clone();
  355. }
  356. }
  357. cv::Mat MapPoint::GetDescriptor()
  358. {
  359. unique_lock<mutex> lock(mMutexFeatures);
  360. return mDescriptor.clone();
  361. }
  362. tuple<int,int> MapPoint::GetIndexInKeyFrame(KeyFrame *pKF)
  363. {
  364. unique_lock<mutex> lock(mMutexFeatures);
  365. if(mObservations.count(pKF))
  366. return mObservations[pKF];
  367. else
  368. return tuple<int,int>(-1,-1);
  369. }
  370. bool MapPoint::IsInKeyFrame(KeyFrame *pKF)
  371. {
  372. unique_lock<mutex> lock(mMutexFeatures);
  373. return (mObservations.count(pKF));
  374. }
  375. void MapPoint::UpdateNormalAndDepth()
  376. {
  377. map<KeyFrame*,tuple<int,int>> observations;
  378. KeyFrame* pRefKF;
  379. cv::Mat Pos;
  380. {
  381. unique_lock<mutex> lock1(mMutexFeatures);
  382. unique_lock<mutex> lock2(mMutexPos);
  383. if(mbBad)
  384. return;
  385. observations=mObservations;
  386. pRefKF=mpRefKF;
  387. Pos = mWorldPos.clone();
  388. }
  389. if(observations.empty())
  390. return;
  391. cv::Mat normal = cv::Mat::zeros(3,1,CV_32F);
  392. int n=0;
  393. for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
  394. {
  395. KeyFrame* pKF = mit->first;
  396. tuple<int,int> indexes = mit -> second;
  397. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  398. if(leftIndex != -1){
  399. cv::Mat Owi = pKF->GetCameraCenter();
  400. cv::Mat normali = mWorldPos - Owi;
  401. normal = normal + normali/cv::norm(normali);
  402. n++;
  403. }
  404. if(rightIndex != -1){
  405. cv::Mat Owi = pKF->GetRightCameraCenter();
  406. cv::Mat normali = mWorldPos - Owi;
  407. normal = normal + normali/cv::norm(normali);
  408. n++;
  409. }
  410. }
  411. cv::Mat PC = Pos - pRefKF->GetCameraCenter();
  412. const float dist = cv::norm(PC);
  413. tuple<int ,int> indexes = observations[pRefKF];
  414. int leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
  415. int level;
  416. if(pRefKF -> NLeft == -1){
  417. level = pRefKF->mvKeysUn[leftIndex].octave;
  418. }
  419. else if(leftIndex != -1){
  420. level = pRefKF -> mvKeys[leftIndex].octave;
  421. }
  422. else{
  423. level = pRefKF -> mvKeysRight[rightIndex - pRefKF -> NLeft].octave;
  424. }
  425. const float levelScaleFactor = pRefKF->mvScaleFactors[level];
  426. const int nLevels = pRefKF->mnScaleLevels;
  427. {
  428. unique_lock<mutex> lock3(mMutexPos);
  429. mfMaxDistance = dist*levelScaleFactor;
  430. mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1];
  431. mNormalVector = normal/n;
  432. mNormalVectorx = cv::Matx31f(mNormalVector.at<float>(0), mNormalVector.at<float>(1), mNormalVector.at<float>(2));
  433. }
  434. }
  435. void MapPoint::SetNormalVector(cv::Mat& normal)
  436. {
  437. unique_lock<mutex> lock3(mMutexPos);
  438. mNormalVector = normal;
  439. mNormalVectorx = cv::Matx31f(mNormalVector.at<float>(0), mNormalVector.at<float>(1), mNormalVector.at<float>(2));
  440. }
  441. float MapPoint::GetMinDistanceInvariance()
  442. {
  443. unique_lock<mutex> lock(mMutexPos);
  444. return 0.8f*mfMinDistance;
  445. }
  446. float MapPoint::GetMaxDistanceInvariance()
  447. {
  448. unique_lock<mutex> lock(mMutexPos);
  449. return 1.2f*mfMaxDistance;
  450. }
  451. int MapPoint::PredictScale(const float &currentDist, KeyFrame* pKF)
  452. {
  453. float ratio;
  454. {
  455. unique_lock<mutex> lock(mMutexPos);
  456. ratio = mfMaxDistance/currentDist;
  457. }
  458. int nScale = ceil(log(ratio)/pKF->mfLogScaleFactor);
  459. if(nScale<0)
  460. nScale = 0;
  461. else if(nScale>=pKF->mnScaleLevels)
  462. nScale = pKF->mnScaleLevels-1;
  463. return nScale;
  464. }
  465. int MapPoint::PredictScale(const float &currentDist, Frame* pF)
  466. {
  467. float ratio;
  468. {
  469. unique_lock<mutex> lock(mMutexPos);
  470. ratio = mfMaxDistance/currentDist;
  471. }
  472. int nScale = ceil(log(ratio)/pF->mfLogScaleFactor);
  473. if(nScale<0)
  474. nScale = 0;
  475. else if(nScale>=pF->mnScaleLevels)
  476. nScale = pF->mnScaleLevels-1;
  477. return nScale;
  478. }
  479. Map* MapPoint::GetMap()
  480. {
  481. unique_lock<mutex> lock(mMutexMap);
  482. return mpMap;
  483. }
  484. void MapPoint::UpdateMap(Map* pMap)
  485. {
  486. unique_lock<mutex> lock(mMutexMap);
  487. mpMap = pMap;
  488. }
  489. } //namespace ORB_SLAM