00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap/core/OdometryORBSLAM2.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/core/util2d.h"
00031 #include "rtabmap/core/util3d_transforms.h"
00032 #include "rtabmap/utilite/ULogger.h"
00033 #include "rtabmap/utilite/UTimer.h"
00034 #include "rtabmap/utilite/UStl.h"
00035 #include "rtabmap/utilite/UDirectory.h"
00036 #include <pcl/common/transforms.h>
00037
00038 #ifdef RTABMAP_ORB_SLAM2
00039 #include <System.h>
00040 #include <thread>
00041
00042 using namespace std;
00043
00044 namespace ORB_SLAM2 {
00045
00046 class Tracker: public Tracking
00047 {
00048 public:
00049 Tracker(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap,
00050 KeyFrameDatabase* pKFDB, const std::string &strSettingPath, const int sensor, long unsigned int maxFeatureMapSize) :
00051 Tracking(pSys, pVoc, pFrameDrawer, pMapDrawer, pMap, pKFDB, strSettingPath, sensor),
00052 maxFeatureMapSize_(maxFeatureMapSize)
00053 {
00054
00055 }
00056 private:
00057 long unsigned int maxFeatureMapSize_;
00058
00059 protected:
00060 void Track()
00061 {
00062 if(mState==NO_IMAGES_YET)
00063 {
00064 mState = NOT_INITIALIZED;
00065 }
00066
00067 mLastProcessedState=mState;
00068
00069
00070 unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
00071
00072 if(mState==NOT_INITIALIZED)
00073 {
00074
00075 StereoInitialization();
00076
00077
00078
00079
00080
00081 if(mState!=OK)
00082 return;
00083 }
00084 else
00085 {
00086
00087 bool bOK;
00088
00089
00090 if(!mbOnlyTracking)
00091 {
00092
00093
00094
00095 if(mState==OK || mState==LOST)
00096 {
00097
00098 CheckReplacedInLastFrame();
00099
00100 if(mVelocity.empty() || mCurrentFrame.mnId<mnLastRelocFrameId+2)
00101 {
00102 bOK = TrackReferenceKeyFrame();
00103 }
00104 else
00105 {
00106 bOK = TrackWithMotionModel();
00107 if(!bOK)
00108 bOK = TrackReferenceKeyFrame();
00109 }
00110 if(bOK)
00111 {
00112 mState=OK;
00113 }
00114 }
00115 else
00116 {
00117 bOK = Relocalization();
00118 }
00119 }
00120 else
00121 {
00122
00123
00124 if(mState==LOST)
00125 {
00126 bOK = Relocalization();
00127 }
00128 else
00129 {
00130 if(!mbVO)
00131 {
00132
00133
00134 if(!mVelocity.empty())
00135 {
00136 bOK = TrackWithMotionModel();
00137 }
00138 else
00139 {
00140 bOK = TrackReferenceKeyFrame();
00141 }
00142 }
00143 else
00144 {
00145
00146
00147
00148
00149
00150
00151 bool bOKMM = false;
00152 bool bOKReloc = false;
00153 std::vector<MapPoint*> vpMPsMM;
00154 std::vector<bool> vbOutMM;
00155 cv::Mat TcwMM;
00156 if(!mVelocity.empty())
00157 {
00158 bOKMM = TrackWithMotionModel();
00159 vpMPsMM = mCurrentFrame.mvpMapPoints;
00160 vbOutMM = mCurrentFrame.mvbOutlier;
00161 TcwMM = mCurrentFrame.mTcw.clone();
00162 }
00163 bOKReloc = Relocalization();
00164
00165 if(bOKMM && !bOKReloc)
00166 {
00167 mCurrentFrame.SetPose(TcwMM);
00168 mCurrentFrame.mvpMapPoints = vpMPsMM;
00169 mCurrentFrame.mvbOutlier = vbOutMM;
00170
00171 if(mbVO)
00172 {
00173 for(int i =0; i<mCurrentFrame.N; i++)
00174 {
00175 if(mCurrentFrame.mvpMapPoints[i] && !mCurrentFrame.mvbOutlier[i])
00176 {
00177 mCurrentFrame.mvpMapPoints[i]->IncreaseFound();
00178 }
00179 }
00180 }
00181 }
00182 else if(bOKReloc)
00183 {
00184 mbVO = false;
00185 }
00186
00187 bOK = bOKReloc || bOKMM;
00188 }
00189 }
00190 }
00191
00192 mCurrentFrame.mpReferenceKF = mpReferenceKF;
00193
00194
00195 if(!mbOnlyTracking)
00196 {
00197 if(bOK)
00198 bOK = TrackLocalMap();
00199 }
00200 else
00201 {
00202
00203
00204
00205 if(bOK && !mbVO)
00206 bOK = TrackLocalMap();
00207 }
00208
00209 if(bOK)
00210 mState = OK;
00211 else
00212 mState=LOST;
00213
00214
00215
00216
00217
00218 if(bOK)
00219 {
00220
00221 if(!mLastFrame.mTcw.empty())
00222 {
00223 cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F);
00224 mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3));
00225 mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3));
00226 mVelocity = mCurrentFrame.mTcw*LastTwc;
00227 }
00228 else
00229 mVelocity = cv::Mat();
00230
00231
00232
00233
00234 for(int i=0; i<mCurrentFrame.N; i++)
00235 {
00236 MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];
00237 if(pMP)
00238 if(pMP->Observations()<1)
00239 {
00240 mCurrentFrame.mvbOutlier[i] = false;
00241 mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
00242 }
00243 }
00244
00245
00246 for(list<MapPoint*>::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++)
00247 {
00248 MapPoint* pMP = *lit;
00249 delete pMP;
00250 }
00251 mlpTemporalPoints.clear();
00252
00253
00254 if(NeedNewKeyFrame())
00255 {
00256 CreateNewKeyFrame();
00257 }
00258
00259 if(maxFeatureMapSize_ > 0)
00260 {
00261
00262 if(mpMap->KeyFramesInMap()>1 && mpMap->MapPointsInMap()>maxFeatureMapSize_)
00263 {
00264 std::vector<KeyFrame*> kfs = mpMap->GetAllKeyFrames();
00265 std::map<long unsigned int, KeyFrame*> kfsSorted;
00266 for(unsigned int i=1; i<kfs.size(); ++i)
00267 {
00268 kfsSorted.insert(std::make_pair(kfs[i]->mnId, kfs[i]));
00269 }
00270 KeyFrame * lastFrame = kfsSorted.rbegin()->second;
00271 std::vector<MapPoint*> mapPoints = mpMap->GetAllMapPoints();
00272 std::map<long unsigned int, MapPoint*> mapPointsSorted;
00273 for(unsigned int i=0; i<mapPoints.size(); ++i)
00274 {
00275 mapPointsSorted.insert(std::make_pair(mapPoints[i]->mnId, mapPoints[i]));
00276 }
00277
00278 for(std::map<long unsigned int, MapPoint*>::iterator iter=mapPointsSorted.begin();
00279 iter != mapPointsSorted.end() && mpMap->MapPointsInMap()>maxFeatureMapSize_;
00280 ++iter)
00281 {
00282 if(!iter->second->IsInKeyFrame(lastFrame))
00283 {
00284
00285
00286
00287 iter->second->SetBadFlag();
00288 }
00289 }
00290
00291 for(std::map<long unsigned int, KeyFrame*>::iterator iter=kfsSorted.begin();
00292 iter != kfsSorted.end();
00293 ++iter)
00294 {
00295 if(iter->second!=lastFrame && iter->second->GetMapPoints().size()==0)
00296 {
00297
00298
00299
00300 iter->second->SetErase();
00301 }
00302 else
00303 {
00304 break;
00305 }
00306 }
00307 }
00308 }
00309
00310
00311
00312
00313
00314 for(int i=0; i<mCurrentFrame.N;i++)
00315 {
00316 if(mCurrentFrame.mvpMapPoints[i] && mCurrentFrame.mvbOutlier[i])
00317 mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
00318 }
00319 }
00320
00321
00322 if(mState==LOST)
00323 {
00324
00325 {
00326 UWARN("Track lost...");
00327 return;
00328
00329 }
00330 }
00331
00332 if(!mCurrentFrame.mpReferenceKF)
00333 mCurrentFrame.mpReferenceKF = mpReferenceKF;
00334
00335 mLastFrame = Frame(mCurrentFrame);
00336 }
00337
00338
00339 if(!mCurrentFrame.mTcw.empty())
00340 {
00341 cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse();
00342 mlRelativeFramePoses.push_back(Tcr);
00343 mlpReferences.push_back(mpReferenceKF);
00344 mlFrameTimes.push_back(mCurrentFrame.mTimeStamp);
00345 mlbLost.push_back(mState==LOST);
00346 }
00347 else
00348 {
00349
00350 mlRelativeFramePoses.push_back(mlRelativeFramePoses.back());
00351 mlpReferences.push_back(mlpReferences.back());
00352 mlFrameTimes.push_back(mlFrameTimes.back());
00353 mlbLost.push_back(mState==LOST);
00354 }
00355 }
00356
00357 void StereoInitialization()
00358 {
00359 if(mCurrentFrame.N>500)
00360 {
00361
00362 mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
00363
00364
00365 KeyFrame* pKFini = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB);
00366
00367
00368 mpMap->AddKeyFrame(pKFini);
00369
00370
00371 for(int i=0; i<mCurrentFrame.N;i++)
00372 {
00373 float z = mCurrentFrame.mvDepth[i];
00374 if(z>0)
00375 {
00376 cv::Mat x3D = mCurrentFrame.UnprojectStereo(i);
00377 MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpMap);
00378 pNewMP->AddObservation(pKFini,i);
00379 pKFini->AddMapPoint(pNewMP,i);
00380 pNewMP->ComputeDistinctiveDescriptors();
00381 pNewMP->UpdateNormalAndDepth();
00382 mpMap->AddMapPoint(pNewMP);
00383
00384 mCurrentFrame.mvpMapPoints[i]=pNewMP;
00385 }
00386 }
00387
00388 cout << "New map created with " << mpMap->MapPointsInMap() << " points" << endl;
00389
00390 mpLocalMapper->InsertKeyFrame(pKFini);
00391
00392 mLastFrame = Frame(mCurrentFrame);
00393 mnLastKeyFrameId=mCurrentFrame.mnId;
00394 mpLastKeyFrame = pKFini;
00395
00396 mvpLocalKeyFrames.push_back(pKFini);
00397 mvpLocalMapPoints=mpMap->GetAllMapPoints();
00398 mpReferenceKF = pKFini;
00399 mCurrentFrame.mpReferenceKF = pKFini;
00400
00401 mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
00402
00403 mpMap->mvpKeyFrameOrigins.push_back(pKFini);
00404
00405
00406
00407 mState=OK;
00408 }
00409 }
00410
00411 public:
00412 cv::Mat GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp)
00413 {
00414 mImGray = imRectLeft;
00415 cv::Mat imGrayRight = imRectRight;
00416
00417 if(mImGray.channels()==3)
00418 {
00419 if(mbRGB)
00420 {
00421 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
00422 }
00423 else
00424 {
00425 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
00426 }
00427 }
00428 else if(mImGray.channels()==4)
00429 {
00430 if(mbRGB)
00431 {
00432 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
00433 }
00434 else
00435 {
00436 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
00437 }
00438 }
00439 if(imGrayRight.channels()==3)
00440 {
00441 if(mbRGB)
00442 {
00443 cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY);
00444 }
00445 else
00446 {
00447 cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY);
00448 }
00449 }
00450 else if(imGrayRight.channels()==4)
00451 {
00452 if(mbRGB)
00453 {
00454 cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY);
00455 }
00456 else
00457 {
00458 cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY);
00459 }
00460 }
00461
00462 mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
00463
00464 Track();
00465
00466 return mCurrentFrame.mTcw.clone();
00467 }
00468
00469 cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp)
00470 {
00471 mImGray = imRGB;
00472 cv::Mat imDepth = imD;
00473
00474 if(mImGray.channels()==3)
00475 {
00476 if(mbRGB)
00477 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
00478 else
00479 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
00480 }
00481 else if(mImGray.channels()==4)
00482 {
00483 if(mbRGB)
00484 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
00485 else
00486 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
00487 }
00488
00489 UASSERT(imDepth.type()==CV_32F);
00490
00491 mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
00492
00493 Track();
00494
00495 return mCurrentFrame.mTcw.clone();
00496 }
00497 };
00498
00499
00500 class LoopCloser: public LoopClosing
00501 {
00502 public:
00503 LoopCloser(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale) :
00504 LoopClosing(pMap, pDB, pVoc, bFixScale)
00505 {
00506 }
00507
00508 public:
00509 void RunNoLoop()
00510 {
00511 mbFinished =false;
00512
00513 while(1)
00514 {
00515
00516 {
00517 unique_lock<mutex> lock(mMutexLoopQueue);
00518 mlpLoopKeyFrameQueue.clear();
00519 }
00520
00521 ResetIfRequested();
00522
00523 if(CheckFinish())
00524 break;
00525
00526 usleep(1000000);
00527 }
00528
00529 SetFinish();
00530 }
00531 };
00532
00533 }
00534
00535 class ORBSLAM2System
00536 {
00537 public:
00538 ORBSLAM2System(const rtabmap::ParametersMap & parameters) :
00539 mpVocabulary(0),
00540 mpKeyFrameDatabase(0),
00541 mpMap(0),
00542 mpTracker(0),
00543 mpLocalMapper(0),
00544 mpLoopCloser(0),
00545 mptLocalMapping(0),
00546 mptLoopClosing(0),
00547 parameters_(parameters)
00548 {
00549 std::string vocabularyPath;
00550 rtabmap::Parameters::parse(parameters, rtabmap::Parameters::kOdomORBSLAM2VocPath(), vocabularyPath);
00551
00552 if(!vocabularyPath.empty())
00553 {
00554
00555 vocabularyPath = uReplaceChar(vocabularyPath, '~', UDirectory::homeDir());
00556 UWARN("Loading ORB Vocabulary: \"%s\". This could take a while...", vocabularyPath.c_str());
00557 mpVocabulary = new ORB_SLAM2::ORBVocabulary();
00558 bool bVocLoad = mpVocabulary->loadFromTextFile(vocabularyPath);
00559 if(!bVocLoad)
00560 {
00561 UERROR("Failed to open vocabulary at %s", vocabularyPath.c_str());
00562 delete mpVocabulary;
00563 mpVocabulary = 0;
00564 }
00565 else
00566 {
00567 UWARN("Vocabulary loaded!");
00568 }
00569 }
00570 else
00571 {
00572 UERROR("ORBSLAM2 vocabulary path should be set! (Parameter name=\"%s\")", rtabmap::Parameters::kOdomORBSLAM2VocPath().c_str());
00573 }
00574 }
00575
00576 bool init(const rtabmap::CameraModel & model, bool stereo, double baseline)
00577 {
00578 if(!mpVocabulary)
00579 {
00580 UERROR("Vocabulary not loaded!");
00581 return false;
00582 }
00583
00584 this->shutdown();
00585
00586
00587 std::string workingDir;
00588 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kRtabmapWorkingDirectory(), workingDir);
00589 if(workingDir.empty())
00590 {
00591 workingDir = ".";
00592 }
00593 std::string configPath = workingDir+"/rtabmap_orbslam2.yaml";
00594 std::ofstream ofs (configPath, std::ofstream::out);
00595 ofs << "%YAML:1.0" << std::endl;
00596 ofs << std::endl;
00597
00598
00599 ofs << "Camera.fx: " << model.fx() << std::endl;
00600 ofs << "Camera.fy: " << model.fy() << std::endl;
00601 ofs << "Camera.cx: " << model.cx() << std::endl;
00602 ofs << "Camera.cy: " << model.cy() << std::endl;
00603 ofs << std::endl;
00604
00605 if(model.D().cols < 4)
00606 {
00607 ofs << "Camera.k1: " << 0 << std::endl;
00608 ofs << "Camera.k2: " << 0 << std::endl;
00609 ofs << "Camera.p1: " << 0 << std::endl;
00610 ofs << "Camera.p2: " << 0 << std::endl;
00611 if(!stereo)
00612 {
00613 ofs << "Camera.k3: " << 0 << std::endl;
00614 }
00615 }
00616 if(model.D().cols >= 4)
00617 {
00618 ofs << "Camera.k1: " << model.D().at<double>(0,0) << std::endl;
00619 ofs << "Camera.k2: " << model.D().at<double>(0,1) << std::endl;
00620 ofs << "Camera.p1: " << model.D().at<double>(0,2) << std::endl;
00621 ofs << "Camera.p2: " << model.D().at<double>(0,3) << std::endl;
00622 }
00623 if(model.D().cols >= 5)
00624 {
00625 ofs << "Camera.k3: " << model.D().at<double>(0,4) << std::endl;
00626 }
00627 if(model.D().cols > 5)
00628 {
00629 UWARN("Unhandled camera distortion size %d, only 5 first coefficients used", model.D().cols);
00630 }
00631 ofs << std::endl;
00632
00633 ofs << "Camera.width: " << model.imageWidth() << std::endl;
00634 ofs << "Camera.height: " << model.imageHeight() << std::endl;
00635 ofs << std::endl;
00636
00637
00638 if(baseline <= 0.0)
00639 {
00640 baseline = rtabmap::Parameters::defaultOdomORBSLAM2Bf();
00641 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAM2Bf(), baseline);
00642 }
00643 ofs << "Camera.bf: " << model.fx()*baseline << std::endl;
00644 ofs << std::endl;
00645
00646
00647
00648 ofs << "Camera.RGB: 1" << std::endl;
00649 ofs << std::endl;
00650
00651 float fps = rtabmap::Parameters::defaultOdomORBSLAM2Fps();
00652 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAM2Fps(), fps);
00653 ofs << "Camera.fps: " << fps << std::endl;
00654 ofs << std::endl;
00655
00656
00657 double thDepth = rtabmap::Parameters::defaultOdomORBSLAM2ThDepth();
00658 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAM2ThDepth(), thDepth);
00659 ofs << "ThDepth: " << thDepth << std::endl;
00660 ofs << std::endl;
00661
00662
00663 ofs << "DepthMapFactor: " << 1000.0 << std::endl;
00664 ofs << std::endl;
00665
00666
00667
00668
00669
00670 int features = rtabmap::Parameters::defaultOdomORBSLAM2MaxFeatures();
00671 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAM2MaxFeatures(), features);
00672 ofs << "ORBextractor.nFeatures: " << features << std::endl;
00673 ofs << std::endl;
00674
00675
00676 double scaleFactor = rtabmap::Parameters::defaultORBScaleFactor();
00677 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kORBScaleFactor(), scaleFactor);
00678 ofs << "ORBextractor.scaleFactor: " << scaleFactor << std::endl;
00679 ofs << std::endl;
00680
00681
00682 int levels = rtabmap::Parameters::defaultORBNLevels();
00683 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kORBNLevels(), levels);
00684 ofs << "ORBextractor.nLevels: " << levels << std::endl;
00685 ofs << std::endl;
00686
00687
00688
00689
00690
00691 int iniThFAST = rtabmap::Parameters::defaultFASTThreshold();
00692 int minThFAST = rtabmap::Parameters::defaultFASTMinThreshold();
00693 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kFASTThreshold(), iniThFAST);
00694 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kFASTMinThreshold(), minThFAST);
00695 ofs << "ORBextractor.iniThFAST: " << iniThFAST << std::endl;
00696 ofs << "ORBextractor.minThFAST: " << minThFAST << std::endl;
00697 ofs << std::endl;
00698
00699 int maxFeatureMapSize = rtabmap::Parameters::defaultOdomORBSLAM2MapSize();
00700 rtabmap::Parameters::parse(parameters_, rtabmap::Parameters::kOdomORBSLAM2MapSize(), maxFeatureMapSize);
00701
00702 ofs.close();
00703
00704
00705 mpKeyFrameDatabase = new ORB_SLAM2::KeyFrameDatabase(*mpVocabulary);
00706
00707
00708 mpMap = new ORB_SLAM2::Map();
00709
00710
00711
00712 mpTracker = new ORB_SLAM2::Tracker(0, mpVocabulary, 0, 0, mpMap, mpKeyFrameDatabase, configPath, stereo?ORB_SLAM2::System::STEREO:ORB_SLAM2::System::RGBD, maxFeatureMapSize);
00713
00714
00715 mpLocalMapper = new ORB_SLAM2::LocalMapping(mpMap, false);
00716
00717
00718 mpLoopCloser = new ORB_SLAM2::LoopCloser(mpMap, mpKeyFrameDatabase, mpVocabulary, true);
00719
00720 mptLocalMapping = new thread(&ORB_SLAM2::LocalMapping::Run, mpLocalMapper);
00721 mptLoopClosing = new thread(&ORB_SLAM2::LoopCloser::RunNoLoop, mpLoopCloser);
00722
00723
00724 mpTracker->SetLocalMapper(mpLocalMapper);
00725 mpTracker->SetLoopClosing(mpLoopCloser);
00726 mpTracker->SetViewer(0);
00727
00728 mpLocalMapper->SetTracker(mpTracker);
00729 mpLocalMapper->SetLoopCloser(mpLoopCloser);
00730
00731 mpLoopCloser->SetTracker(mpTracker);
00732 mpLoopCloser->SetLocalMapper(mpLocalMapper);
00733
00734 return true;
00735 }
00736
00737 virtual ~ORBSLAM2System()
00738 {
00739 shutdown();
00740 delete mpVocabulary;
00741 }
00742
00743 void shutdown()
00744 {
00745 if(mpMap)
00746 {
00747 mpLocalMapper->RequestFinish();
00748 mpLoopCloser->RequestFinish();
00749
00750
00751 while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA())
00752 {
00753 usleep(5000);
00754 }
00755
00756
00757 mptLoopClosing->join();
00758 delete mptLoopClosing;
00759 mptLoopClosing = 0;
00760 mptLocalMapping->join();
00761 delete mptLocalMapping;
00762 mptLocalMapping = 0;
00763 delete mpLoopCloser;
00764 mpLoopCloser=0;
00765 delete mpLocalMapper;
00766 mpLocalMapper=0;
00767 delete mpTracker;
00768 mpTracker=0;
00769 delete mpMap;
00770 mpMap=0;
00771 delete mpKeyFrameDatabase;
00772 mpKeyFrameDatabase=0;
00773 }
00774 }
00775
00776 public:
00777
00778 ORB_SLAM2::ORBVocabulary* mpVocabulary;
00779
00780
00781 ORB_SLAM2::KeyFrameDatabase* mpKeyFrameDatabase;
00782
00783
00784 ORB_SLAM2::Map* mpMap;
00785
00786
00787
00788
00789 ORB_SLAM2::Tracker* mpTracker;
00790
00791
00792 ORB_SLAM2::LocalMapping* mpLocalMapper;
00793
00794
00795
00796 ORB_SLAM2::LoopCloser* mpLoopCloser;
00797
00798
00799
00800 std::thread* mptLocalMapping;
00801 std::thread* mptLoopClosing;
00802
00803 rtabmap::ParametersMap parameters_;
00804 };
00805 #endif
00806
00807 namespace rtabmap {
00808
00809 OdometryORBSLAM2::OdometryORBSLAM2(const ParametersMap & parameters) :
00810 Odometry(parameters)
00811 #ifdef RTABMAP_ORB_SLAM2
00812 ,
00813 orbslam2_(0),
00814 firstFrame_(true),
00815 previousPose_(Transform::getIdentity())
00816 #endif
00817 {
00818 #ifdef RTABMAP_ORB_SLAM2
00819 orbslam2_ = new ORBSLAM2System(parameters);
00820 #endif
00821 }
00822
00823 OdometryORBSLAM2::~OdometryORBSLAM2()
00824 {
00825 #ifdef RTABMAP_ORB_SLAM2
00826 if(orbslam2_)
00827 {
00828 delete orbslam2_;
00829 }
00830 #endif
00831 }
00832
00833 void OdometryORBSLAM2::reset(const Transform & initialPose)
00834 {
00835 Odometry::reset(initialPose);
00836 #ifdef RTABMAP_ORB_SLAM2
00837 if(orbslam2_)
00838 {
00839 orbslam2_->shutdown();
00840 }
00841 firstFrame_ = true;
00842 originLocalTransform_.setNull();
00843 previousPose_.setIdentity();
00844 #endif
00845 }
00846
00847
00848 Transform OdometryORBSLAM2::computeTransform(
00849 SensorData & data,
00850 const Transform & guess,
00851 OdometryInfo * info)
00852 {
00853 Transform t;
00854
00855 #ifdef RTABMAP_ORB_SLAM2
00856 UTimer timer;
00857
00858 if(data.imageRaw().empty() ||
00859 data.imageRaw().rows != data.depthOrRightRaw().rows ||
00860 data.imageRaw().cols != data.depthOrRightRaw().cols)
00861 {
00862 UERROR("Not supported input! RGB (%dx%d) and depth (%dx%d) should have the same size.",
00863 data.imageRaw().cols, data.imageRaw().rows, data.depthOrRightRaw().cols, data.depthOrRightRaw().rows);
00864 return t;
00865 }
00866
00867 if(!((data.cameraModels().size() == 1 &&
00868 data.cameraModels()[0].isValidForReprojection()) ||
00869 (data.stereoCameraModel().isValidForProjection() &&
00870 data.stereoCameraModel().left().isValidForReprojection() &&
00871 data.stereoCameraModel().right().isValidForReprojection())))
00872 {
00873 UERROR("Invalid camera model!");
00874 return t;
00875 }
00876
00877 bool stereo = data.cameraModels().size() == 0;
00878
00879 cv::Mat covariance;
00880 if(orbslam2_->mpTracker == 0)
00881 {
00882 CameraModel model = data.cameraModels().size()==1?data.cameraModels()[0]:data.stereoCameraModel().left();
00883 if(!orbslam2_->init(model, stereo, data.stereoCameraModel().baseline()))
00884 {
00885 return t;
00886 }
00887 }
00888
00889 cv::Mat Tcw;
00890 Transform localTransform;
00891 if(stereo)
00892 {
00893 localTransform = data.stereoCameraModel().localTransform();
00894 Tcw = ((ORB_SLAM2::Tracker*)orbslam2_->mpTracker)->GrabImageStereo(data.imageRaw(), data.rightRaw(), data.stamp());
00895 }
00896 else
00897 {
00898 localTransform = data.cameraModels()[0].localTransform();
00899 cv::Mat depth;
00900 if(data.depthRaw().type() == CV_32FC1)
00901 {
00902 depth = data.depthRaw();
00903 }
00904 else if(data.depthRaw().type() == CV_16UC1)
00905 {
00906 depth = util2d::cvtDepthToFloat(data.depthRaw());
00907 }
00908 Tcw = ((ORB_SLAM2::Tracker*)orbslam2_->mpTracker)->GrabImageRGBD(data.imageRaw(), depth, data.stamp());
00909 }
00910
00911 Transform previousPoseInv = previousPose_.inverse();
00912 if(orbslam2_->mpTracker->mState == ORB_SLAM2::Tracking::LOST)
00913 {
00914 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
00915 }
00916 else if(Tcw.cols == 4 && Tcw.rows == 4)
00917 {
00918 Transform p = Transform(cv::Mat(Tcw, cv::Range(0,3), cv::Range(0,4)));
00919
00920 if(!p.isNull())
00921 {
00922 if(!localTransform.isNull())
00923 {
00924 if(originLocalTransform_.isNull())
00925 {
00926 originLocalTransform_ = localTransform;
00927 }
00928
00929 p = originLocalTransform_ * p.inverse() * localTransform.inverse();
00930 }
00931 t = previousPoseInv*p;
00932 }
00933 previousPose_ = p;
00934
00935 if(firstFrame_)
00936 {
00937
00938 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
00939 firstFrame_ = false;
00940 }
00941 else
00942 {
00943 float baseline = data.stereoCameraModel().baseline();
00944 if(baseline <= 0.0f)
00945 {
00946 baseline = rtabmap::Parameters::defaultOdomORBSLAM2Bf();
00947 rtabmap::Parameters::parse(orbslam2_->parameters_, rtabmap::Parameters::kOdomORBSLAM2Bf(), baseline);
00948 }
00949 double linearVar = 0.0001;
00950 if(baseline > 0.0f)
00951 {
00952 linearVar = baseline/8.0;
00953 linearVar *= linearVar;
00954 }
00955
00956 covariance = cv::Mat::eye(6,6, CV_64FC1);
00957 covariance.at<double>(0,0) = linearVar;
00958 covariance.at<double>(1,1) = linearVar;
00959 covariance.at<double>(2,2) = linearVar;
00960 covariance.at<double>(3,3) = 0.0001;
00961 covariance.at<double>(4,4) = 0.0001;
00962 covariance.at<double>(5,5) = 0.0001;
00963 }
00964 }
00965
00966 int totalMapPoints= 0;
00967 int totalKfs= 0;
00968 if(orbslam2_->mpMap)
00969 {
00970 totalMapPoints = orbslam2_->mpMap->MapPointsInMap();
00971 totalKfs = orbslam2_->mpMap->KeyFramesInMap();
00972 }
00973
00974 if(info)
00975 {
00976 info->lost = t.isNull();
00977 info->type = (int)kTypeORBSLAM2;
00978 info->reg.covariance = covariance;
00979 info->localMapSize = totalMapPoints;
00980 info->localKeyFrames = totalKfs;
00981
00982 if(this->isInfoDataFilled() && orbslam2_->mpTracker && orbslam2_->mpMap)
00983 {
00984 const std::vector<cv::KeyPoint> & kpts = orbslam2_->mpTracker->mCurrentFrame.mvKeys;
00985 info->reg.matchesIDs.resize(kpts.size());
00986 info->reg.inliersIDs.resize(kpts.size());
00987 int oi = 0;
00988 for (unsigned int i = 0; i < kpts.size(); ++i)
00989 {
00990 int wordId;
00991 if(orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
00992 {
00993 wordId = orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i]->mnId;
00994 }
00995 else
00996 {
00997 wordId = -(i+1);
00998 }
00999 info->words.insert(std::make_pair(wordId, kpts[i]));
01000 if(orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
01001 {
01002 info->reg.matchesIDs[oi] = wordId;
01003 info->reg.inliersIDs[oi] = wordId;
01004 ++oi;
01005 }
01006 }
01007 info->reg.matchesIDs.resize(oi);
01008 info->reg.inliersIDs.resize(oi);
01009 info->reg.inliers = oi;
01010 info->reg.matches = oi;
01011
01012 std::vector<ORB_SLAM2::MapPoint*> mapPoints = orbslam2_->mpMap->GetAllMapPoints();
01013 Eigen::Affine3f fixRot = (this->getPose()*previousPoseInv*originLocalTransform_).toEigen3f();
01014 for (unsigned int i = 0; i < mapPoints.size(); ++i)
01015 {
01016 cv::Point3f pt(mapPoints[i]->GetWorldPos());
01017 pcl::PointXYZ ptt = pcl::transformPoint(pcl::PointXYZ(pt.x, pt.y, pt.z), fixRot);
01018 info->localMap.insert(std::make_pair(mapPoints[i]->mnId, cv::Point3f(ptt.x, ptt.y, ptt.z)));
01019 }
01020 }
01021 }
01022
01023 UINFO("Odom update time = %fs, map points=%d, keyframes=%d, lost=%s", timer.elapsed(), totalMapPoints, totalKfs, t.isNull()?"true":"false");
01024
01025 #else
01026 UERROR("RTAB-Map is not built with ORB_SLAM2 support! Select another visual odometry approach.");
01027 #endif
01028 return t;
01029 }
01030
01031 }