OdometryORBSLAM2.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "rtabmap/core/util2d.h"
32 #include "rtabmap/utilite/UTimer.h"
33 #include "rtabmap/utilite/UStl.h"
35 #include <pcl/common/transforms.h>
36 #include <opencv2/imgproc/types_c.h>
38 
39 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
40 #include <System.h>
41 #include <thread>
42 
43 using namespace std;
44 
45 namespace ORB_SLAM2 {
46 
47 // Override original Tracking object to comment all rendering stuff
48 class Tracker: public Tracking
49 {
50 public:
51  Tracker(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap,
52  KeyFrameDatabase* pKFDB, const std::string &strSettingPath, const int sensor, long unsigned int maxFeatureMapSize) :
53  Tracking(pSys, pVoc, pFrameDrawer, pMapDrawer, pMap, pKFDB, strSettingPath, sensor),
54  maxFeatureMapSize_(maxFeatureMapSize)
55  {}
56 
57 private:
58  long unsigned int maxFeatureMapSize_;
59 
60 protected:
61  void Track()
62  {
63  if(mState==NO_IMAGES_YET)
64  {
65  mState = NOT_INITIALIZED;
66  }
67 
68  mLastProcessedState=mState;
69 
70  // Get Map Mutex -> Map cannot be changed
71  unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
72 
73  if(mState==NOT_INITIALIZED)
74  {
75  // if(mSensor==System::STEREO || mSensor==System::RGBD)
76  StereoInitialization();
77  //else
78  // MonocularInitialization();
79 
80  //mpFrameDrawer->Update(this);
81 
82  if(mState!=OK)
83  {
84  return;
85  }
86  }
87  else
88  {
89  // System is initialized. Track Frame.
90  bool bOK = true;
91 
92  // Initial camera pose estimation using motion model or relocalization (if tracking is lost)
93  if(!mbOnlyTracking)
94  {
95  // Local Mapping is activated. This is the normal behaviour, unless
96  // you explicitly activate the "only tracking" mode.
97 
98  if(mState==OK || mState==LOST)
99  {
100  // Local Mapping might have changed some MapPoints tracked in last frame
101  CheckReplacedInLastFrame();
102 
103  if(mVelocity.empty() || mCurrentFrame.mnId<mnLastRelocFrameId+2)
104  {
105  bOK = TrackReferenceKeyFrame();
106  }
107  else
108  {
109  bOK = TrackWithMotionModel();
110  if(!bOK)
111  bOK = TrackReferenceKeyFrame();
112  }
113  if(bOK)
114  {
115  mState=OK;
116  }
117  }
118  else
119  {
120  bOK = Relocalization();
121  }
122  }
123  else
124  {
125  // Localization Mode: Local Mapping is deactivated
126 
127  if(mState==LOST)
128  {
129  bOK = Relocalization();
130  }
131  else
132  {
133  if(!mbVO)
134  {
135  // In last frame we tracked enough MapPoints in the map
136 
137  if(!mVelocity.empty())
138  {
139  bOK = TrackWithMotionModel();
140  }
141  else
142  {
143  bOK = TrackReferenceKeyFrame();
144  }
145  }
146  else
147  {
148  // In last frame we tracked mainly "visual odometry" points.
149 
150  // We compute two camera poses, one from motion model and one doing relocalization.
151  // If relocalization is sucessfull we choose that solution, otherwise we retain
152  // the "visual odometry" solution.
153 
154  bool bOKMM = false;
155  bool bOKReloc = false;
156  std::vector<MapPoint*> vpMPsMM;
157  std::vector<bool> vbOutMM;
158  cv::Mat TcwMM;
159  if(!mVelocity.empty())
160  {
161  bOKMM = TrackWithMotionModel();
162  vpMPsMM = mCurrentFrame.mvpMapPoints;
163  vbOutMM = mCurrentFrame.mvbOutlier;
164  TcwMM = mCurrentFrame.mTcw.clone();
165  }
166  bOKReloc = Relocalization();
167 
168  if(bOKMM && !bOKReloc)
169  {
170  mCurrentFrame.SetPose(TcwMM);
171  mCurrentFrame.mvpMapPoints = vpMPsMM;
172  mCurrentFrame.mvbOutlier = vbOutMM;
173 
174  if(mbVO)
175  {
176  for(int i =0; i<mCurrentFrame.N; i++)
177  {
178  if(mCurrentFrame.mvpMapPoints[i] && !mCurrentFrame.mvbOutlier[i])
179  {
180  mCurrentFrame.mvpMapPoints[i]->IncreaseFound();
181  }
182  }
183  }
184  }
185  else if(bOKReloc)
186  {
187  mbVO = false;
188  }
189 
190  bOK = bOKReloc || bOKMM;
191  }
192  }
193  }
194 
195  if(!mCurrentFrame.mpReferenceKF)
196  mCurrentFrame.mpReferenceKF = mpReferenceKF;
197 
198  // If we have an initial estimation of the camera pose and matching. Track the local map.
199  if(!mbOnlyTracking)
200  {
201  if(bOK)
202  bOK = TrackLocalMap();
203  }
204  else
205  {
206  // mbVO true means that there are few matches to MapPoints in the map. We cannot retrieve
207  // a local map and therefore we do not perform TrackLocalMap(). Once the system relocalizes
208  // the camera we will use the local map again.
209  if(bOK && !mbVO)
210  bOK = TrackLocalMap();
211  }
212 
213  if(bOK)
214  mState = OK;
215  else
216  mState=LOST;
217 
218  // Update drawer
219  //mpFrameDrawer->Update(this);
220 
221  // If tracking were good, check if we insert a keyframe
222  if(bOK)
223  {
224  // Update motion model
225  if(!mLastFrame.mTcw.empty())
226  {
227  cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F);
228  mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3));
229  mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3));
230  mVelocity = mCurrentFrame.mTcw*LastTwc;
231  }
232  else
233  mVelocity = cv::Mat();
234 
235  //mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
236 
237  // Clean VO matches
238  for(int i=0; i<mCurrentFrame.N; i++)
239  {
240  MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];
241  if(pMP)
242  if(pMP->Observations()<1)
243  {
244  mCurrentFrame.mvbOutlier[i] = false;
245  mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
246  }
247  }
248 
249  // Delete temporal MapPoints
250  for(list<MapPoint*>::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++)
251  {
252  MapPoint* pMP = *lit;
253  delete pMP;
254  }
255  mlpTemporalPoints.clear();
256 
257  // Check if we need to insert a new keyframe
258  if(NeedNewKeyFrame())
259  {
260  CreateNewKeyFrame();
261  }
262 
263  if(maxFeatureMapSize_ > 0)
264  {
265  //limit size of the feature map, keep last X recent ones
266  if(mpMap->KeyFramesInMap()>1 && mpMap->MapPointsInMap()>maxFeatureMapSize_)
267  {
268  std::vector<KeyFrame*> kfs = mpMap->GetAllKeyFrames();
269  std::map<long unsigned int, KeyFrame*> kfsSorted;
270  for(unsigned int i=1; i<kfs.size(); ++i)
271  {
272  kfsSorted.insert(std::make_pair(kfs[i]->mnId, kfs[i]));
273  }
274  KeyFrame * lastFrame = kfsSorted.rbegin()->second;
275  std::vector<MapPoint*> mapPoints = mpMap->GetAllMapPoints();
276  std::map<long unsigned int, MapPoint*> mapPointsSorted;
277  for(unsigned int i=0; i<mapPoints.size(); ++i)
278  {
279  mapPointsSorted.insert(std::make_pair(mapPoints[i]->mnId, mapPoints[i]));
280  }
281 
282  for(std::map<long unsigned int, MapPoint*>::iterator iter=mapPointsSorted.begin();
283  iter != mapPointsSorted.end() && mpMap->MapPointsInMap()>maxFeatureMapSize_;
284  ++iter)
285  {
286  if(!iter->second->IsInKeyFrame(lastFrame))
287  {
288  // FIXME: Memory leak: ORB_SLAM2 doesn't delete after removing from the map...
289  // Not sure when it is safe to delete it, as if I delete just
290  // after setting the bad flag, the app crashes.
291  iter->second->SetBadFlag();
292  }
293  }
294  // remove kfs without observations
295  for(std::map<long unsigned int, KeyFrame*>::iterator iter=kfsSorted.begin();
296  iter != kfsSorted.end();
297  ++iter)
298  {
299  if(iter->second!=lastFrame && iter->second->GetMapPoints().size()==0)
300  {
301  // FIXME: Memory leak: ORB_SLAM2 doesn't delete after removing from the map...
302  // Not sure when it is safe to delete it, as if I delete just
303  // after setting the bad flag, the app crashes.
304  iter->second->SetErase();
305  }
306  else
307  {
308  break;
309  }
310  }
311  }
312  }
313 
314  // We allow points with high innovation (considererd outliers by the Huber Function)
315  // pass to the new keyframe, so that bundle adjustment will finally decide
316  // if they are outliers or not. We don't want next frame to estimate its position
317  // with those points so we discard them in the frame.
318  for(int i=0; i<mCurrentFrame.N;i++)
319  {
320  if(mCurrentFrame.mvpMapPoints[i] && mCurrentFrame.mvbOutlier[i])
321  mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
322  }
323  }
324 
325  // Reset if the camera get lost soon after initialization
326  if(mState==LOST)
327  {
328  //if(mpMap->KeyFramesInMap()<=5)
329  {
330  UWARN("Track lost...");
331  return;
332 
333  }
334  }
335 
336  if(!mCurrentFrame.mpReferenceKF)
337  mCurrentFrame.mpReferenceKF = mpReferenceKF;
338 
339  mLastFrame = Frame(mCurrentFrame);
340  }
341 
342  // Store frame pose information to retrieve the complete camera trajectory afterwards.
343  if(!mCurrentFrame.mTcw.empty())
344  {
345  cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse();
346  mlRelativeFramePoses.push_back(Tcr);
347  mlpReferences.push_back(mpReferenceKF);
348  mlFrameTimes.push_back(mCurrentFrame.mTimeStamp);
349  mlbLost.push_back(mState==LOST);
350  }
351  else
352  {
353  // This can happen if tracking is lost
354  mlRelativeFramePoses.push_back(mlRelativeFramePoses.back());
355  mlpReferences.push_back(mlpReferences.back());
356  mlFrameTimes.push_back(mlFrameTimes.back());
357  mlbLost.push_back(mState==LOST);
358  }
359  }
360 
361  void StereoInitialization()
362  {
363  if(mCurrentFrame.N>500)
364  {
365  // Set Frame pose to the origin
366  mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
367 
368  // Create KeyFrame
369  KeyFrame* pKFini = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB);
370 
371  // Insert KeyFrame in the map
372  mpMap->AddKeyFrame(pKFini);
373 
374  // Create MapPoints and asscoiate to KeyFrame
375  for(int i=0; i<mCurrentFrame.N;i++)
376  {
377  float z = mCurrentFrame.mvDepth[i];
378  if(z>0)
379  {
380  cv::Mat x3D = mCurrentFrame.UnprojectStereo(i);
381  MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpMap);
382  pNewMP->AddObservation(pKFini,i);
383  pKFini->AddMapPoint(pNewMP,i);
384  pNewMP->ComputeDistinctiveDescriptors();
385  pNewMP->UpdateNormalAndDepth();
386  mpMap->AddMapPoint(pNewMP);
387 
388  mCurrentFrame.mvpMapPoints[i]=pNewMP;
389  }
390  }
391 
392  cout << "New map created with " << mpMap->MapPointsInMap() << " points" << endl;
393 
394  mpLocalMapper->InsertKeyFrame(pKFini);
395 
396  mLastFrame = Frame(mCurrentFrame);
397  mnLastKeyFrameId=mCurrentFrame.mnId;
398  mpLastKeyFrame = pKFini;
399 
400  mvpLocalKeyFrames.push_back(pKFini);
401  mvpLocalMapPoints=mpMap->GetAllMapPoints();
402  mpReferenceKF = pKFini;
403  mCurrentFrame.mpReferenceKF = pKFini;
404 
405  mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
406 
407  mpMap->mvpKeyFrameOrigins.push_back(pKFini);
408 
409  //mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
410 
411  mState=OK;
412  }
413  }
414 
415 public:
416  cv::Mat GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double &timestamp)
417  {
418  mImGray = imRectLeft;
419  cv::Mat imGrayRight = imRectRight;
420 
421  if(mImGray.channels()==3)
422  {
423  if(mbRGB)
424  {
425  cvtColor(mImGray,mImGray,CV_RGB2GRAY);
426  }
427  else
428  {
429  cvtColor(mImGray,mImGray,CV_BGR2GRAY);
430  }
431  }
432  else if(mImGray.channels()==4)
433  {
434  if(mbRGB)
435  {
436  cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
437  }
438  else
439  {
440  cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
441  }
442  }
443  if(imGrayRight.channels()==3)
444  {
445  if(mbRGB)
446  {
447  cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY);
448  }
449  else
450  {
451  cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY);
452  }
453  }
454  else if(imGrayRight.channels()==4)
455  {
456  if(mbRGB)
457  {
458  cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY);
459  }
460  else
461  {
462  cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY);
463  }
464  }
465 
466  mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
467 
468  Track();
469 
470  return mCurrentFrame.mTcw.clone();
471  }
472 
473  cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp)
474  {
475  mImGray = imRGB;
476  cv::Mat imDepth = imD;
477 
478  if(mImGray.channels()==3)
479  {
480  if(mbRGB)
481  cvtColor(mImGray,mImGray,CV_RGB2GRAY);
482  else
483  cvtColor(mImGray,mImGray,CV_BGR2GRAY);
484  }
485  else if(mImGray.channels()==4)
486  {
487  if(mbRGB)
488  cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
489  else
490  cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
491  }
492 
493  UASSERT(imDepth.type()==CV_32F);
494 
495  mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
496 
497  Track();
498 
499  return mCurrentFrame.mTcw.clone();
500  }
501 };
502 
503 // Hack to disable loop closing
504 class LoopCloser: public LoopClosing
505 {
506 public:
507  LoopCloser(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale) :
508  LoopClosing(pMap, pDB, pVoc, bFixScale)
509  {}
510 
511 public:
512  void RunNoLoop()
513  {
514  mbFinished =false;
515 
516  while(1)
517  {
518  // just clear the buffer
519  {
520  unique_lock<mutex> lock(mMutexLoopQueue);
521  mlpLoopKeyFrameQueue.clear();
522  }
523 
524  ResetIfRequested();
525 
526  if(CheckFinish())
527  break;
528 
529  usleep(1000000); // 1 sec
530  }
531 
532  SetFinish();
533  }
534 };
535 
536 } // namespace ORB_SLAM
537 
538 using namespace ORB_SLAM2;
539 
540 class ORBSLAM2System
541 {
542 public:
543  ORBSLAM2System(const rtabmap::ParametersMap & parameters) :
544  mpVocabulary(0),
545  mpKeyFrameDatabase(0),
546  mpMap(0),
547  mpTracker(0),
548  mpLocalMapper(0),
549  mpLoopCloser(0),
550  mptLocalMapping(0),
551  mptLoopClosing(0),
552  parameters_(parameters)
553  {
554  std::string vocabularyPath;
555  rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kOdomORBSLAMVocPath(), vocabularyPath);
556 
557  if(!vocabularyPath.empty())
558  {
559  //Load ORB Vocabulary
560  vocabularyPath = uReplaceChar(vocabularyPath, '~', UDirectory::homeDir());
561  UWARN("Loading ORB Vocabulary: \"%s\". This could take a while...", vocabularyPath.c_str());
562  mpVocabulary = new ORBVocabulary();
563  bool bVocLoad = mpVocabulary->loadFromTextFile(vocabularyPath);
564  if(!bVocLoad)
565  {
566  UERROR("Failed to open vocabulary at %s", vocabularyPath.c_str());
567  delete mpVocabulary;
568  mpVocabulary = 0;
569  }
570  else
571  {
572  UWARN("Vocabulary loaded!");
573  }
574  }
575  else
576  {
577  UERROR("ORBSLAM2 vocabulary path should be set! (Parameter name=\"%s\")", rtabmap::Parameters::kOdomORBSLAMVocPath().c_str());
578  }
579  }
580 
581  bool init(const rtabmap::CameraModel & model, bool stereo, double baseline)
582  {
583  if(!mpVocabulary)
584  {
585  UERROR("Vocabulary not loaded!");
586  return false;
587  }
588 
589  this->shutdown();
590 
591  // Create configuration file
592  std::string workingDir;
593  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
594  if(workingDir.empty())
595  {
596  workingDir = ".";
597  }
598  std::string configPath = workingDir+"/rtabmap_orbslam.yaml";
599  std::ofstream ofs (configPath, std::ofstream::out);
600  ofs << "%YAML:1.0" << std::endl;
601  ofs << std::endl;
602 
603 
604  ofs << "Camera.type: \"PinHole\"" << std::endl;
605  ofs << std::endl;
606 
607  ofs << fixed << setprecision(13);
608 
609  //# Camera calibration and distortion parameters (OpenCV)
610  ofs << "Camera.fx: " << model.fx() << std::endl;
611  ofs << "Camera.fy: " << model.fy() << std::endl;
612  ofs << "Camera.cx: " << model.cx() << std::endl;
613  ofs << "Camera.cy: " << model.cy() << std::endl;
614  ofs << std::endl;
615 
616  if(model.D().cols < 4)
617  {
618  ofs << "Camera.k1: " << 0.0 << std::endl;
619  ofs << "Camera.k2: " << 0.0 << std::endl;
620  ofs << "Camera.p1: " << 0.0 << std::endl;
621  ofs << "Camera.p2: " << 0.0 << std::endl;
622  if(!stereo)
623  {
624  ofs << "Camera.k3: " << 0.0 << std::endl;
625  }
626  }
627  if(model.D().cols >= 4)
628  {
629  ofs << "Camera.k1: " << model.D().at<double>(0,0) << std::endl;
630  ofs << "Camera.k2: " << model.D().at<double>(0,1) << std::endl;
631  ofs << "Camera.p1: " << model.D().at<double>(0,2) << std::endl;
632  ofs << "Camera.p2: " << model.D().at<double>(0,3) << std::endl;
633  }
634  if(model.D().cols >= 5)
635  {
636  ofs << "Camera.k3: " << model.D().at<double>(0,4) << std::endl;
637  }
638  if(model.D().cols > 5)
639  {
640  UWARN("Unhandled camera distortion size %d, only 5 first coefficients used", model.D().cols);
641  }
642  ofs << std::endl;
643 
644  ofs << "Camera.width: " << model.imageWidth() << std::endl;
645  ofs << "Camera.height: " << model.imageHeight() << std::endl;
646  ofs << std::endl;
647 
648  //# IR projector baseline times fx (aprox.)
649  if(baseline <= 0.0)
650  {
651  baseline = rtabmap::Parameters::defaultOdomORBSLAMBf();
652  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAMBf(), baseline);
653  }
654  ofs << "Camera.bf: " << model.fx()*baseline << std::endl;
655  ofs << std::endl;
656 
657  //# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
658  //Camera.RGB: 1
659  ofs << "Camera.RGB: 1" << std::endl;
660  ofs << std::endl;
661 
662  float fps = rtabmap::Parameters::defaultOdomORBSLAMFps();
663  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAMFps(), fps);
664  ofs << "Camera.fps: " << fps << std::endl;
665  ofs << std::endl;
666 
667  //# Close/Far threshold. Baseline times.
668  double thDepth = rtabmap::Parameters::defaultOdomORBSLAMThDepth();
669  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAMThDepth(), thDepth);
670  ofs << "ThDepth: " << thDepth << std::endl;
671  ofs << std::endl;
672 
673  //# Deptmap values factor
674  ofs << "DepthMapFactor: " << 1000.0 << std::endl;
675  ofs << std::endl;
676 
677  //#--------------------------------------------------------------------------------------------
678  //# ORB Parameters
679  //#--------------------------------------------------------------------------------------------
680  //# ORB Extractor: Number of features per image
681  int features = rtabmap::Parameters::defaultOdomORBSLAMMaxFeatures();
682  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAMMaxFeatures(), features);
683  ofs << "ORBextractor.nFeatures: " << features << std::endl;
684  ofs << std::endl;
685 
686  //# ORB Extractor: Scale factor between levels in the scale pyramid
687  double scaleFactor = rtabmap::Parameters::defaultORBScaleFactor();
688  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kORBScaleFactor(), scaleFactor);
689  ofs << "ORBextractor.scaleFactor: " << scaleFactor << std::endl;
690  ofs << std::endl;
691 
692  //# ORB Extractor: Number of levels in the scale pyramid
693  int levels = rtabmap::Parameters::defaultORBNLevels();
694  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kORBNLevels(), levels);
695  ofs << "ORBextractor.nLevels: " << levels << std::endl;
696  ofs << std::endl;
697 
698  //# ORB Extractor: Fast threshold
699  //# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
700  //# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
701  //# You can lower these values if your images have low contrast
702  int iniThFAST = rtabmap::Parameters::defaultFASTThreshold();
703  int minThFAST = rtabmap::Parameters::defaultFASTMinThreshold();
704  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kFASTThreshold(), iniThFAST);
705  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kFASTMinThreshold(), minThFAST);
706  ofs << "ORBextractor.iniThFAST: " << iniThFAST << std::endl;
707  ofs << "ORBextractor.minThFAST: " << minThFAST << std::endl;
708  ofs << std::endl;
709 
710  int maxFeatureMapSize = rtabmap::Parameters::defaultOdomORBSLAMMapSize();
711  rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAMMapSize(), maxFeatureMapSize);
712 
713  ofs.close();
714 
715  //Create KeyFrame Database
716  mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
717 
718  //Create the Map
719  mpMap = new ORB_SLAM2::Map();
720 
721  //Initialize the Tracking thread
722  //(it will live in the main thread of execution, the one that called this constructor)
723  mpTracker = new Tracker(0, mpVocabulary, 0, 0, mpMap, mpKeyFrameDatabase, configPath, stereo?System::STEREO:System::RGBD, maxFeatureMapSize);
724 
725  //Initialize the Local Mapping thread and launch
726  mpLocalMapper = new LocalMapping(mpMap, false);
727 
728  //Initialize the Loop Closing thread and launch
729  mpLoopCloser = new LoopCloser(mpMap, mpKeyFrameDatabase, mpVocabulary, true);
730 
731  mptLocalMapping = new thread(&LocalMapping::Run, mpLocalMapper);
732  mptLoopClosing = new thread(&LoopCloser::RunNoLoop, mpLoopCloser);
733 
734  //Set pointers between threads
735  mpTracker->SetLocalMapper(mpLocalMapper);
736  mpTracker->SetLoopClosing(mpLoopCloser);
737  mpTracker->SetViewer(0);
738 
739  mpLocalMapper->SetTracker(mpTracker);
740  mpLocalMapper->SetLoopCloser(mpLoopCloser);
741 
742  mpLoopCloser->SetTracker(mpTracker);
743  mpLoopCloser->SetLocalMapper(mpLocalMapper);
744 
745  // Reset all static variables
746  Frame::mbInitialComputations = true;
747 
748  return true;
749  }
750 
751  virtual ~ORBSLAM2System()
752  {
753  shutdown();
754  delete mpVocabulary;
755  }
756 
757  void shutdown()
758  {
759  if(mpMap)
760  {
761  mpLocalMapper->RequestFinish();
762  mpLoopCloser->RequestFinish();
763 
764  // Wait until all thread have effectively stopped
765  while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA())
766  {
767  usleep(5000);
768  }
769 
770  //cleanup!
771  mptLoopClosing->join();
772  delete mptLoopClosing;
773  mptLoopClosing = 0;
774  mptLocalMapping->join();
775  delete mptLocalMapping;
776  mptLocalMapping = 0;
777  delete mpLoopCloser;
778  mpLoopCloser=0;
779  delete mpLocalMapper;
780  mpLocalMapper=0;
781  delete mpTracker;
782  mpTracker=0;
783  delete mpMap;
784  mpMap=0;
785  delete mpKeyFrameDatabase;
786  mpKeyFrameDatabase=0;
787  }
788  }
789 
790 public:
791  // ORB vocabulary used for place recognition and feature matching.
792  ORBVocabulary* mpVocabulary;
793 
794  // KeyFrame database for place recognition (relocalization and loop detection).
795  KeyFrameDatabase* mpKeyFrameDatabase;
796 
797  // Map structure that stores the pointers to all KeyFrames and MapPoints.
798  Map* mpMap;
799 
800  // Tracker. It receives a frame and computes the associated camera pose.
801  // It also decides when to insert a new keyframe, create some new MapPoints and
802  // performs relocalization if tracking fails.
803  Tracker* mpTracker;
804 
805  // Local Mapper. It manages the local map and performs local bundle adjustment.
806  LocalMapping* mpLocalMapper;
807 
808  // Loop Closer. It searches loops with every new keyframe. If there is a loop it performs
809  // a pose graph optimization and full bundle adjustment (in a new thread) afterwards.
810  LoopCloser* mpLoopCloser;
811 
812  // System threads: Local Mapping, Loop Closing, Viewer.
813  // The Tracking thread "lives" in the main execution thread that creates the System object.
814  std::thread* mptLocalMapping;
815  std::thread* mptLoopClosing;
816 
817  rtabmap::ParametersMap parameters_;
818 };
819 #endif
820 
821 namespace rtabmap {
822 
823 OdometryORBSLAM2::OdometryORBSLAM2(const ParametersMap & parameters) :
824  Odometry(parameters)
825 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
826  ,
827  orbslam_(0),
828  firstFrame_(true),
829  previousPose_(Transform::getIdentity())
830 #endif
831 {
832 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
833  orbslam_ = new ORBSLAM2System(parameters);
834 #endif
835 }
836 
838 {
839 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
840  if(orbslam_)
841  {
842  delete orbslam_;
843  }
844 #endif
845 }
846 
847 void OdometryORBSLAM2::reset(const Transform & initialPose)
848 {
849  Odometry::reset(initialPose);
850 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
851  if(orbslam_)
852  {
853  orbslam_->shutdown();
854  }
855  firstFrame_ = true;
856  originLocalTransform_.setNull();
857  previousPose_.setIdentity();
858 #endif
859 }
860 
861 // return not null transform if odometry is correctly computed
863  SensorData & data,
864  const Transform & guess,
865  OdometryInfo * info)
866 {
867  Transform t;
868 
869 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
870  UTimer timer;
871 
872  if(data.imageRaw().empty() ||
873  data.imageRaw().rows != data.depthOrRightRaw().rows ||
874  data.imageRaw().cols != data.depthOrRightRaw().cols)
875  {
876  UERROR("Not supported input! RGB (%dx%d) and depth (%dx%d) should have the same size.",
877  data.imageRaw().cols, data.imageRaw().rows, data.depthOrRightRaw().cols, data.depthOrRightRaw().rows);
878  return t;
879  }
880 
881  if(!((data.cameraModels().size() == 1 &&
882  data.cameraModels()[0].isValidForReprojection()) ||
883  (data.stereoCameraModels().size() == 1 &&
884  data.stereoCameraModels()[0].isValidForProjection())))
885  {
886  UERROR("Invalid camera model!");
887  return t;
888  }
889 
890  bool stereo = data.cameraModels().size() == 0;
891 
892  cv::Mat covariance;
893  if(orbslam_->mpTracker == 0)
894  {
895  CameraModel model = data.cameraModels().size()==1?data.cameraModels()[0]:data.stereoCameraModels()[0].left();
896  if(!orbslam_->init(model, stereo, data.cameraModels().size()==1?0.0f:data.stereoCameraModels()[0].baseline()))
897  {
898  return t;
899  }
900  }
901 
902  cv::Mat Tcw;
903  Transform localTransform;
904  if(stereo)
905  {
906  localTransform = data.stereoCameraModels()[0].localTransform();
907  Tcw = ((Tracker*)orbslam_->mpTracker)->GrabImageStereo(data.imageRaw(), data.rightRaw(), data.stamp());
908  }
909  else
910  {
911  localTransform = data.cameraModels()[0].localTransform();
912  cv::Mat depth;
913  if(data.depthRaw().type() == CV_32FC1)
914  {
915  depth = data.depthRaw();
916  }
917  else if(data.depthRaw().type() == CV_16UC1)
918  {
919  depth = util2d::cvtDepthToFloat(data.depthRaw());
920  }
921  Tcw = ((Tracker*)orbslam_->mpTracker)->GrabImageRGBD(data.imageRaw(), depth, data.stamp());
922  }
923 
924  Transform previousPoseInv = previousPose_.inverse();
925  if(orbslam_->mpTracker->mState == Tracking::LOST)
926  {
927  covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
928  }
929  else if(Tcw.cols == 4 && Tcw.rows == 4)
930  {
931  Transform p = Transform(cv::Mat(Tcw, cv::Range(0,3), cv::Range(0,4)));
932 
933  if(!p.isNull())
934  {
935  if(!localTransform.isNull())
936  {
937  if(originLocalTransform_.isNull())
938  {
939  originLocalTransform_ = localTransform;
940  }
941  // transform in base frame
942  p = originLocalTransform_ * p.inverse() * localTransform.inverse();
943  }
944  t = previousPoseInv*p;
945  }
946  previousPose_ = p;
947 
948  if(firstFrame_)
949  {
950  // just recovered of being lost, set high covariance
951  covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
952  firstFrame_ = false;
953  }
954  else
955  {
956  float baseline = data.cameraModels().size()==1?0.0f:data.stereoCameraModels()[0].baseline();
957  if(baseline <= 0.0f)
958  {
959  baseline = rtabmap::Parameters::defaultOdomORBSLAMBf();
960  rtabmap::Parameters::parse(orbslam_->parameters_, rtabmap::Parameters::kOdomORBSLAMBf(), baseline);
961  }
962  double linearVar = 0.0001;
963  if(baseline > 0.0f)
964  {
965  linearVar = baseline/8.0;
966  linearVar *= linearVar;
967  }
968 
969  covariance = cv::Mat::eye(6,6, CV_64FC1);
970  covariance.at<double>(0,0) = linearVar;
971  covariance.at<double>(1,1) = linearVar;
972  covariance.at<double>(2,2) = linearVar;
973  covariance.at<double>(3,3) = 0.0001;
974  covariance.at<double>(4,4) = 0.0001;
975  covariance.at<double>(5,5) = 0.0001;
976  }
977  }
978 
979  int totalMapPoints= 0;
980  int totalKfs= 0;
981  if(orbslam_->mpMap)
982  {
983  totalMapPoints = orbslam_->mpMap->MapPointsInMap();
984  totalKfs = orbslam_->mpMap->KeyFramesInMap();
985  }
986 
987  if(info)
988  {
989  info->lost = t.isNull();
990  info->type = (int)kTypeORBSLAM;
991  info->reg.covariance = covariance;
992  info->localMapSize = totalMapPoints;
993  info->localKeyFrames = totalKfs;
994 
995  if(this->isInfoDataFilled() && orbslam_->mpTracker && orbslam_->mpMap)
996  {
997  const std::vector<cv::KeyPoint> & kpts = orbslam_->mpTracker->mCurrentFrame.mvKeys;
998  info->reg.matchesIDs.resize(kpts.size());
999  info->reg.inliersIDs.resize(kpts.size());
1000  int oi = 0;
1001  for (unsigned int i = 0; i < kpts.size(); ++i)
1002  {
1003  int wordId;
1004  if(orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
1005  {
1006  wordId = orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[i]->mnId;
1007  }
1008  else
1009  {
1010  wordId = -(i+1);
1011  }
1012  info->words.insert(std::make_pair(wordId, kpts[i]));
1013  if(orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
1014  {
1015  info->reg.matchesIDs[oi] = wordId;
1016  info->reg.inliersIDs[oi] = wordId;
1017  ++oi;
1018  }
1019  }
1020  info->reg.matchesIDs.resize(oi);
1021  info->reg.inliersIDs.resize(oi);
1022  info->reg.inliers = oi;
1023  info->reg.matches = oi;
1024 
1025  std::vector<MapPoint*> mapPoints = orbslam_->mpMap->GetAllMapPoints();
1026  Eigen::Affine3f fixRot = (this->getPose()*previousPoseInv*originLocalTransform_).toEigen3f();
1027  for (unsigned int i = 0; i < mapPoints.size(); ++i)
1028  {
1029  cv::Point3f pt(mapPoints[i]->GetWorldPos());
1030  pcl::PointXYZ ptt = pcl::transformPoint(pcl::PointXYZ(pt.x, pt.y, pt.z), fixRot);
1031  info->localMap.insert(std::make_pair(mapPoints[i]->mnId, cv::Point3f(ptt.x, ptt.y, ptt.z)));
1032  }
1033  }
1034  }
1035 
1036  UINFO("Odom update time = %fs, map points=%d, keyframes=%d, lost=%s", timer.elapsed(), totalMapPoints, totalKfs, t.isNull()?"true":"false");
1037 
1038 #else
1039  UERROR("RTAB-Map is not built with ORB_SLAM support! Select another visual odometry approach.");
1040 #endif
1041  return t;
1042 }
1043 
1044 } // namespace rtabmap
rtabmap::SensorData
Definition: SensorData.h:51
int
int
UINFO
#define UINFO(...)
OdometryInfo.h
Eigen::Transform
timer
list
rtabmap::OdometryORBSLAM2::computeTransform
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
Definition: OdometryORBSLAM2.cpp:862
UDirectory.h
rtabmap::CameraModel
Definition: CameraModel.h:38
OdometryORBSLAM2.h
if
if(ret >=0) *info
true
#define true
Definition: ConvertUTF.c:57
rtabmap::util2d::cvtDepthToFloat
cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat(const cv::Mat &depth16U)
Definition: util2d.cpp:928
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
UTimer.h
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:500
rtabmap::OdometryORBSLAM2::reset
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: OdometryORBSLAM2.cpp:847
rtabmap::OdometryORBSLAM2::~OdometryORBSLAM2
virtual ~OdometryORBSLAM2()
Definition: OdometryORBSLAM2.cpp:837
UDirectory::homeDir
static std::string homeDir()
Definition: UDirectory.cpp:355
rtabmap::Odometry::getPose
const Transform & getPose() const
Definition: Odometry.h:76
rtabmap::util3d::transformPoint
cv::Point3f RTABMAP_CORE_EXPORT transformPoint(const cv::Point3f &pt, const Transform &transform)
Definition: util3d_transforms.cpp:211
data
int data[]
util3d_transforms.h
shutdown
ROSCONSOLE_DECL void shutdown()
rtabmap::Odometry::reset
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:210
info
else if n * info
UASSERT
#define UASSERT(condition)
z
z
p
Point3_ p(2)
rtabmap::Transform::inverse
Transform inverse() const
Definition: Transform.cpp:178
UWARN
#define UWARN(...)
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
timer::elapsed
double elapsed() const
uReplaceChar
std::string UTILITE_EXPORT uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:33
rtabmap_netvlad.init
def init(descriptorDim)
Definition: rtabmap_netvlad.py:30
ULogger.h
ULogger class and convenient macros.
rtabmap::Transform
Definition: Transform.h:41
util2d.h
iter
iterator iter(handle obj)
std
rtabmap::Odometry::kTypeORBSLAM
@ kTypeORBSLAM
Definition: Odometry.h:52
c_str
const char * c_str(Args &&...args)
UStl.h
Wrappers of STL for convenient functions.
rtabmap::Odometry
Definition: Odometry.h:42
UTimer
Definition: UTimer.h:46
rtabmap::OdometryInfo
Definition: OdometryInfo.h:40
NULL
#define NULL
t
Point2 t(10, 10)
rtabmap
Definition: CameraARCore.cpp:35
UERROR
#define UERROR(...)
trace.model
model
Definition: trace.py:4
i
int i
baseline
double baseline
rtabmap::Odometry::isInfoDataFilled
bool isInfoDataFilled() const
Definition: Odometry.h:77
cvtColor
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
list::begin
detail::list_iterator begin() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:13