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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29