MapPoint.cc
Go to the documentation of this file.
1 
21 #include "MapPoint.h"
22 #include "ORBmatcher.h"
23 
24 #include<mutex>
25 
26 namespace ORB_SLAM2
27 {
28 
29 long unsigned int MapPoint::nNextId=0;
31 
32 MapPoint::MapPoint(const cv::Mat &Pos, KeyFrame *pRefKF, Map* pMap):
33  mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0),
34  mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0),
35  mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false),
36  mpReplaced(static_cast<MapPoint*>(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap)
37 {
38  Pos.copyTo(mWorldPos);
39  mNormalVector = cv::Mat::zeros(3,1,CV_32F);
40 
41  // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
42  unique_lock<mutex> lock(mpMap->mMutexPointCreation);
43  mnId=nNextId++;
44 }
45 
46 MapPoint::MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF):
49  mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(static_cast<KeyFrame*>(NULL)), mnVisible(1),
50  mnFound(1), mbBad(false), mpReplaced(NULL), mpMap(pMap)
51 {
52  Pos.copyTo(mWorldPos);
53  cv::Mat Ow = pFrame->GetCameraCenter();
54  mNormalVector = mWorldPos - Ow;
56 
57  cv::Mat PC = Pos - Ow;
58  const float dist = cv::norm(PC);
59  const int level = pFrame->mvKeysUn[idxF].octave;
60  const float levelScaleFactor = pFrame->mvScaleFactors[level];
61  const int nLevels = pFrame->mnScaleLevels;
62 
63  mfMaxDistance = dist*levelScaleFactor;
64  mfMinDistance = mfMaxDistance/pFrame->mvScaleFactors[nLevels-1];
65 
66  pFrame->mDescriptors.row(idxF).copyTo(mDescriptor);
67 
68  // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id.
69  unique_lock<mutex> lock(mpMap->mMutexPointCreation);
70  mnId=nNextId++;
71 }
72 
73 void MapPoint::SetWorldPos(const cv::Mat &Pos)
74 {
75  unique_lock<mutex> lock2(mGlobalMutex);
76  unique_lock<mutex> lock(mMutexPos);
77  Pos.copyTo(mWorldPos);
78 }
79 
81 {
82  unique_lock<mutex> lock(mMutexPos);
83  return mWorldPos.clone();
84 }
85 
87 {
88  unique_lock<mutex> lock(mMutexPos);
89  return mNormalVector.clone();
90 }
91 
93 {
94  unique_lock<mutex> lock(mMutexFeatures);
95  return mpRefKF;
96 }
97 
98 void MapPoint::AddObservation(KeyFrame* pKF, size_t idx)
99 {
100  unique_lock<mutex> lock(mMutexFeatures);
101  if(mObservations.count(pKF))
102  return;
103  mObservations[pKF]=idx;
104 
105  if(pKF->mvuRight[idx]>=0)
106  nObs+=2;
107  else
108  nObs++;
109 }
110 
112 {
113  bool bBad=false;
114  {
115  unique_lock<mutex> lock(mMutexFeatures);
116  if(mObservations.count(pKF))
117  {
118  int idx = mObservations[pKF];
119  if(pKF->mvuRight[idx]>=0)
120  nObs-=2;
121  else
122  nObs--;
123 
124  mObservations.erase(pKF);
125 
126  if(mpRefKF==pKF)
127  mpRefKF=mObservations.begin()->first;
128 
129  // If only 2 observations or less, discard point
130  if(nObs<=2)
131  bBad=true;
132  }
133  }
134 
135  if(bBad)
136  SetBadFlag();
137 }
138 
139 map<KeyFrame*, size_t> MapPoint::GetObservations()
140 {
141  unique_lock<mutex> lock(mMutexFeatures);
142  return mObservations;
143 }
144 
146 {
147  unique_lock<mutex> lock(mMutexFeatures);
148  return nObs;
149 }
150 
152 {
153  map<KeyFrame*,size_t> obs;
154  {
155  unique_lock<mutex> lock1(mMutexFeatures);
156  unique_lock<mutex> lock2(mMutexPos);
157  mbBad=true;
158  obs = mObservations;
159  mObservations.clear();
160  }
161  for(map<KeyFrame*,size_t>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
162  {
163  KeyFrame* pKF = mit->first;
164  pKF->EraseMapPointMatch(mit->second);
165  }
166 
167  mpMap->EraseMapPoint(this);
168 }
169 
171 {
172  unique_lock<mutex> lock1(mMutexFeatures);
173  unique_lock<mutex> lock2(mMutexPos);
174  return mpReplaced;
175 }
176 
178 {
179  if(pMP->mnId==this->mnId)
180  return;
181 
182  int nvisible, nfound;
183  map<KeyFrame*,size_t> obs;
184  {
185  unique_lock<mutex> lock1(mMutexFeatures);
186  unique_lock<mutex> lock2(mMutexPos);
187  obs=mObservations;
188  mObservations.clear();
189  mbBad=true;
190  nvisible = mnVisible;
191  nfound = mnFound;
192  mpReplaced = pMP;
193  }
194 
195  for(map<KeyFrame*,size_t>::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++)
196  {
197  // Replace measurement in keyframe
198  KeyFrame* pKF = mit->first;
199 
200  if(!pMP->IsInKeyFrame(pKF))
201  {
202  pKF->ReplaceMapPointMatch(mit->second, pMP);
203  pMP->AddObservation(pKF,mit->second);
204  }
205  else
206  {
207  pKF->EraseMapPointMatch(mit->second);
208  }
209  }
210  pMP->IncreaseFound(nfound);
211  pMP->IncreaseVisible(nvisible);
213 
214  mpMap->EraseMapPoint(this);
215 }
216 
218 {
219  unique_lock<mutex> lock(mMutexFeatures);
220  unique_lock<mutex> lock2(mMutexPos);
221  return mbBad;
222 }
223 
225 {
226  unique_lock<mutex> lock(mMutexFeatures);
227  mnVisible+=n;
228 }
229 
231 {
232  unique_lock<mutex> lock(mMutexFeatures);
233  mnFound+=n;
234 }
235 
237 {
238  unique_lock<mutex> lock(mMutexFeatures);
239  return static_cast<float>(mnFound)/mnVisible;
240 }
241 
243 {
244  // Retrieve all observed descriptors
245  vector<cv::Mat> vDescriptors;
246 
247  map<KeyFrame*,size_t> observations;
248 
249  {
250  unique_lock<mutex> lock1(mMutexFeatures);
251  if(mbBad)
252  return;
253  observations=mObservations;
254  }
255 
256  if(observations.empty())
257  return;
258 
259  vDescriptors.reserve(observations.size());
260 
261  for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
262  {
263  KeyFrame* pKF = mit->first;
264 
265  if(!pKF->isBad())
266  vDescriptors.push_back(pKF->mDescriptors.row(mit->second));
267  }
268 
269  if(vDescriptors.empty())
270  return;
271 
272  // Compute distances between them
273  const size_t N = vDescriptors.size();
274 
275  float Distances[N][N];
276  for(size_t i=0;i<N;i++)
277  {
278  Distances[i][i]=0;
279  for(size_t j=i+1;j<N;j++)
280  {
281  int distij = ORBmatcher::DescriptorDistance(vDescriptors[i],vDescriptors[j]);
282  Distances[i][j]=distij;
283  Distances[j][i]=distij;
284  }
285  }
286 
287  // Take the descriptor with least median distance to the rest
288  int BestMedian = INT_MAX;
289  int BestIdx = 0;
290  for(size_t i=0;i<N;i++)
291  {
292  vector<int> vDists(Distances[i],Distances[i]+N);
293  sort(vDists.begin(),vDists.end());
294  int median = vDists[0.5*(N-1)];
295 
296  if(median<BestMedian)
297  {
298  BestMedian = median;
299  BestIdx = i;
300  }
301  }
302 
303  {
304  unique_lock<mutex> lock(mMutexFeatures);
305  mDescriptor = vDescriptors[BestIdx].clone();
306  }
307 }
308 
310 {
311  unique_lock<mutex> lock(mMutexFeatures);
312  return mDescriptor.clone();
313 }
314 
316 {
317  unique_lock<mutex> lock(mMutexFeatures);
318  if(mObservations.count(pKF))
319  return mObservations[pKF];
320  else
321  return -1;
322 }
323 
325 {
326  unique_lock<mutex> lock(mMutexFeatures);
327  return (mObservations.count(pKF));
328 }
329 
331 {
332  map<KeyFrame*,size_t> observations;
333  KeyFrame* pRefKF;
334  cv::Mat Pos;
335  {
336  unique_lock<mutex> lock1(mMutexFeatures);
337  unique_lock<mutex> lock2(mMutexPos);
338  if(mbBad)
339  return;
340  observations=mObservations;
341  pRefKF=mpRefKF;
342  Pos = mWorldPos.clone();
343  }
344 
345  if(observations.empty())
346  return;
347 
348  cv::Mat normal = cv::Mat::zeros(3,1,CV_32F);
349  int n=0;
350  for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
351  {
352  KeyFrame* pKF = mit->first;
353  cv::Mat Owi = pKF->GetCameraCenter();
354  cv::Mat normali = mWorldPos - Owi;
355  normal = normal + normali/cv::norm(normali);
356  n++;
357  }
358 
359  cv::Mat PC = Pos - pRefKF->GetCameraCenter();
360  const float dist = cv::norm(PC);
361  const int level = pRefKF->mvKeysUn[observations[pRefKF]].octave;
362  const float levelScaleFactor = pRefKF->mvScaleFactors[level];
363  const int nLevels = pRefKF->mnScaleLevels;
364 
365  {
366  unique_lock<mutex> lock3(mMutexPos);
367  mfMaxDistance = dist*levelScaleFactor;
368  mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1];
369  mNormalVector = normal/n;
370  }
371 }
372 
374 {
375  unique_lock<mutex> lock(mMutexPos);
376  return 0.8f*mfMinDistance;
377 }
378 
380 {
381  unique_lock<mutex> lock(mMutexPos);
382  return 1.2f*mfMaxDistance;
383 }
384 
385 int MapPoint::PredictScale(const float &currentDist, KeyFrame* pKF)
386 {
387  float ratio;
388  {
389  unique_lock<mutex> lock(mMutexPos);
390  ratio = mfMaxDistance/currentDist;
391  }
392 
393  int nScale = ceil(log(ratio)/pKF->mfLogScaleFactor);
394  if(nScale<0)
395  nScale = 0;
396  else if(nScale>=pKF->mnScaleLevels)
397  nScale = pKF->mnScaleLevels-1;
398 
399  return nScale;
400 }
401 
402 int MapPoint::PredictScale(const float &currentDist, Frame* pF)
403 {
404  float ratio;
405  {
406  unique_lock<mutex> lock(mMutexPos);
407  ratio = mfMaxDistance/currentDist;
408  }
409 
410  int nScale = ceil(log(ratio)/pF->mfLogScaleFactor);
411  if(nScale<0)
412  nScale = 0;
413  else if(nScale>=pF->mnScaleLevels)
414  nScale = pF->mnScaleLevels-1;
415 
416  return nScale;
417 }
418 
419 // map serialization addition
424  mpReplaced(static_cast<MapPoint*>(NULL)), mfMinDistance(0), mfMaxDistance(0)
425 {}
426 template<class Archive>
427 void MapPoint::serialize(Archive &ar, const unsigned int version)
428 {
429  unique_lock<mutex> lock_Pos(mMutexPos);
430  unique_lock<mutex> lock_Features(mMutexFeatures);
432  // Tracking related vars
433  ar & mTrackProjX;
434  ar & mTrackProjY;
435  ar & mTrackProjXR;
436  ar & mbTrackInView;
437  ar & mnTrackScaleLevel;
438  ar & mTrackViewCos;
440  ar & mnLastFrameSeen;
441  // Local Mapping related vars
443  // Loop Closing related vars
445  // don't save the mutex
446  ar & mWorldPos;
447  ar & mObservations;
448  ar & mNormalVector;
449  ar & mDescriptor;
450  ar & mpRefKF;
451  ar & mnVisible & mnFound;
452  ar & mbBad & mpReplaced;
454  ar & mpMap;
455  // don't save the mutex
456 }
457 template void MapPoint::serialize(boost::archive::binary_iarchive&, const unsigned int);
458 template void MapPoint::serialize(boost::archive::binary_oarchive&, const unsigned int);
459 
460 } //namespace ORB_SLAM
float GetMinDistanceInvariance()
Definition: MapPoint.cc:373
void EraseMapPointMatch(const size_t &idx)
Definition: KeyFrame.cc:216
std::mutex mMutexPointCreation
Definition: Map.h:68
long unsigned int mnBALocalForKF
Definition: MapPoint.h:103
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
long unsigned int mnBAGlobalForKF
Definition: MapPoint.h:111
cv::Mat GetCameraCenter()
Definition: KeyFrame.cc:98
void EraseMapPoint(MapPoint *pMP)
Definition: Map.cc:46
std::mutex mMutexFeatures
Definition: MapPoint.h:148
const std::vector< float > mvScaleFactors
Definition: KeyFrame.h:181
float GetFoundRatio()
Definition: MapPoint.cc:236
long unsigned int mnLoopPointForKF
Definition: MapPoint.h:107
static long unsigned int nNextId
Definition: MapPoint.h:87
long int mnFirstKFid
Definition: MapPoint.h:88
cv::Mat mNormalVector
Definition: MapPoint.h:125
long unsigned int mnCorrectedByKF
Definition: MapPoint.h:108
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
void ReplaceMapPointMatch(const size_t &idx, MapPoint *pMP)
Definition: KeyFrame.cc:230
KeyFrame * mpRefKF
Definition: MapPoint.h:131
void IncreaseVisible(int n=1)
Definition: MapPoint.cc:224
void AddObservation(KeyFrame *pKF, size_t idx)
Definition: MapPoint.cc:98
cv::Mat GetDescriptor()
Definition: MapPoint.cc:309
void UpdateNormalAndDepth()
Definition: MapPoint.cc:330
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
cv::Mat mDescriptor
Definition: MapPoint.h:128
cv::Mat GetCameraCenter()
Definition: Frame.h:73
static std::mutex mGlobalMutex
Definition: MapPoint.h:114
std::map< KeyFrame *, size_t > GetObservations()
Definition: MapPoint.cc:139
int mnScaleLevels
Definition: Frame.h:174
void IncreaseFound(int n=1)
Definition: MapPoint.cc:230
const int mnScaleLevels
Definition: KeyFrame.h:178
KeyFrame * GetReferenceKeyFrame()
Definition: MapPoint.cc:92
float mfLogScaleFactor
Definition: Frame.h:176
void Replace(MapPoint *pMP)
Definition: MapPoint.cc:177
std::mutex mMutexPos
Definition: MapPoint.h:147
std::map< KeyFrame *, size_t > mObservations
Definition: MapPoint.h:122
void SetWorldPos(const cv::Mat &Pos)
Definition: MapPoint.cc:73
MapPoint * GetReplaced()
Definition: MapPoint.cc:170
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
Definition: ORBmatcher.cc:1647
float GetMaxDistanceInvariance()
Definition: MapPoint.cc:379
vector< float > mvScaleFactors
Definition: Frame.h:177
cv::Mat GetNormal()
Definition: MapPoint.cc:86
long unsigned int mnLastFrameSeen
Definition: MapPoint.h:100
MapPoint * mpReplaced
Definition: MapPoint.h:139
long int mnFirstFrame
Definition: MapPoint.h:89
const std::vector< float > mvuRight
Definition: KeyFrame.h:166
int GetIndexInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:315
void serialize(Archive &ar, const unsigned int version)
Definition: MapPoint.cc:427
long unsigned int mnTrackReferenceForFrame
Definition: MapPoint.h:99
cv::Mat mDescriptors
Definition: Frame.h:150
long unsigned int mnCorrectedReference
Definition: MapPoint.h:109
void ComputeDistinctiveDescriptors()
Definition: MapPoint.cc:242
long unsigned int mnId
Definition: MapPoint.h:86
const cv::Mat mDescriptors
Definition: KeyFrame.h:168
bool IsInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:324
int PredictScale(const float &currentDist, KeyFrame *pKF)
Definition: MapPoint.cc:385
long unsigned int mnFuseCandidateForKF
Definition: MapPoint.h:104
const float mfLogScaleFactor
Definition: KeyFrame.h:180
void EraseObservation(KeyFrame *pKF)
Definition: MapPoint.cc:111


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05