35 #include <pcl/common/transforms.h>
36 #include <opencv2/imgproc/types_c.h>
39 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
48 class Tracker:
public Tracking
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)
58 long unsigned int maxFeatureMapSize_;
63 if(mState==NO_IMAGES_YET)
65 mState = NOT_INITIALIZED;
68 mLastProcessedState=mState;
71 unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
73 if(mState==NOT_INITIALIZED)
76 StereoInitialization();
98 if(mState==OK || mState==LOST)
101 CheckReplacedInLastFrame();
103 if(mVelocity.empty() || mCurrentFrame.mnId<mnLastRelocFrameId+2)
105 bOK = TrackReferenceKeyFrame();
109 bOK = TrackWithMotionModel();
111 bOK = TrackReferenceKeyFrame();
120 bOK = Relocalization();
129 bOK = Relocalization();
137 if(!mVelocity.empty())
139 bOK = TrackWithMotionModel();
143 bOK = TrackReferenceKeyFrame();
155 bool bOKReloc =
false;
156 std::vector<MapPoint*> vpMPsMM;
157 std::vector<bool> vbOutMM;
159 if(!mVelocity.empty())
161 bOKMM = TrackWithMotionModel();
162 vpMPsMM = mCurrentFrame.mvpMapPoints;
163 vbOutMM = mCurrentFrame.mvbOutlier;
164 TcwMM = mCurrentFrame.mTcw.clone();
166 bOKReloc = Relocalization();
168 if(bOKMM && !bOKReloc)
170 mCurrentFrame.SetPose(TcwMM);
171 mCurrentFrame.mvpMapPoints = vpMPsMM;
172 mCurrentFrame.mvbOutlier = vbOutMM;
176 for(
int i =0;
i<mCurrentFrame.N;
i++)
178 if(mCurrentFrame.mvpMapPoints[i] && !mCurrentFrame.mvbOutlier[i])
180 mCurrentFrame.mvpMapPoints[
i]->IncreaseFound();
190 bOK = bOKReloc || bOKMM;
195 if(!mCurrentFrame.mpReferenceKF)
196 mCurrentFrame.mpReferenceKF = mpReferenceKF;
202 bOK = TrackLocalMap();
210 bOK = TrackLocalMap();
225 if(!mLastFrame.mTcw.empty())
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;
233 mVelocity = cv::Mat();
238 for(
int i=0;
i<mCurrentFrame.N;
i++)
240 MapPoint* pMP = mCurrentFrame.mvpMapPoints[
i];
242 if(pMP->Observations()<1)
244 mCurrentFrame.mvbOutlier[
i] =
false;
245 mCurrentFrame.mvpMapPoints[
i]=
static_cast<MapPoint*
>(
NULL);
252 MapPoint* pMP = *lit;
255 mlpTemporalPoints.clear();
258 if(NeedNewKeyFrame())
263 if(maxFeatureMapSize_ > 0)
266 if(mpMap->KeyFramesInMap()>1 && mpMap->MapPointsInMap()>maxFeatureMapSize_)
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)
272 kfsSorted.insert(std::make_pair(kfs[i]->mnId, kfs[i]));
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)
279 mapPointsSorted.insert(std::make_pair(mapPoints[i]->mnId, mapPoints[i]));
282 for(std::map<long unsigned int, MapPoint*>::iterator
iter=mapPointsSorted.begin();
283 iter != mapPointsSorted.end() && mpMap->MapPointsInMap()>maxFeatureMapSize_;
286 if(!
iter->second->IsInKeyFrame(lastFrame))
291 iter->second->SetBadFlag();
295 for(std::map<long unsigned int, KeyFrame*>::iterator
iter=kfsSorted.begin();
296 iter != kfsSorted.end();
299 if(
iter->second!=lastFrame &&
iter->second->GetMapPoints().size()==0)
304 iter->second->SetErase();
318 for(
int i=0;
i<mCurrentFrame.N;
i++)
320 if(mCurrentFrame.mvpMapPoints[i] && mCurrentFrame.mvbOutlier[i])
321 mCurrentFrame.mvpMapPoints[
i]=
static_cast<MapPoint*
>(
NULL);
330 UWARN(
"Track lost...");
336 if(!mCurrentFrame.mpReferenceKF)
337 mCurrentFrame.mpReferenceKF = mpReferenceKF;
339 mLastFrame = Frame(mCurrentFrame);
343 if(!mCurrentFrame.mTcw.empty())
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);
354 mlRelativeFramePoses.push_back(mlRelativeFramePoses.back());
355 mlpReferences.push_back(mlpReferences.back());
356 mlFrameTimes.push_back(mlFrameTimes.back());
357 mlbLost.push_back(mState==LOST);
361 void StereoInitialization()
363 if(mCurrentFrame.N>500)
366 mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
369 KeyFrame* pKFini =
new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB);
372 mpMap->AddKeyFrame(pKFini);
375 for(
int i=0;
i<mCurrentFrame.N;
i++)
377 float z = mCurrentFrame.mvDepth[
i];
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);
388 mCurrentFrame.mvpMapPoints[
i]=pNewMP;
392 cout <<
"New map created with " << mpMap->MapPointsInMap() <<
" points" << endl;
394 mpLocalMapper->InsertKeyFrame(pKFini);
396 mLastFrame = Frame(mCurrentFrame);
397 mnLastKeyFrameId=mCurrentFrame.mnId;
398 mpLastKeyFrame = pKFini;
400 mvpLocalKeyFrames.push_back(pKFini);
401 mvpLocalMapPoints=mpMap->GetAllMapPoints();
402 mpReferenceKF = pKFini;
403 mCurrentFrame.mpReferenceKF = pKFini;
405 mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
407 mpMap->mvpKeyFrameOrigins.push_back(pKFini);
416 cv::Mat GrabImageStereo(
const cv::Mat &imRectLeft,
const cv::Mat &imRectRight,
const double ×tamp)
418 mImGray = imRectLeft;
419 cv::Mat imGrayRight = imRectRight;
421 if(mImGray.channels()==3)
425 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
429 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
432 else if(mImGray.channels()==4)
436 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
440 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
443 if(imGrayRight.channels()==3)
447 cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY);
451 cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY);
454 else if(imGrayRight.channels()==4)
458 cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY);
462 cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY);
466 mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
470 return mCurrentFrame.mTcw.clone();
473 cv::Mat GrabImageRGBD(
const cv::Mat &imRGB,
const cv::Mat &imD,
const double ×tamp)
476 cv::Mat imDepth = imD;
478 if(mImGray.channels()==3)
481 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
483 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
485 else if(mImGray.channels()==4)
488 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
490 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
493 UASSERT(imDepth.type()==CV_32F);
495 mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
499 return mCurrentFrame.mTcw.clone();
504 class LoopCloser:
public LoopClosing
507 LoopCloser(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,
const bool bFixScale) :
508 LoopClosing(pMap, pDB, pVoc, bFixScale)
520 unique_lock<mutex> lock(mMutexLoopQueue);
521 mlpLoopKeyFrameQueue.clear();
538 using namespace ORB_SLAM2;
545 mpKeyFrameDatabase(0),
552 parameters_(parameters)
554 std::string vocabularyPath;
557 if(!vocabularyPath.empty())
561 UWARN(
"Loading ORB Vocabulary: \"%s\". This could take a while...", vocabularyPath.c_str());
562 mpVocabulary =
new ORBVocabulary();
563 bool bVocLoad = mpVocabulary->loadFromTextFile(vocabularyPath);
566 UERROR(
"Failed to open vocabulary at %s", vocabularyPath.c_str());
572 UWARN(
"Vocabulary loaded!");
577 UERROR(
"ORBSLAM2 vocabulary path should be set! (Parameter name=\"%s\")", rtabmap::Parameters::kOdomORBSLAMVocPath().
c_str());
585 UERROR(
"Vocabulary not loaded!");
592 std::string workingDir;
594 if(workingDir.empty())
598 std::string configPath = workingDir+
"/rtabmap_orbslam.yaml";
599 std::ofstream ofs (configPath, std::ofstream::out);
600 ofs <<
"%YAML:1.0" << std::endl;
604 ofs <<
"Camera.type: \"PinHole\"" << std::endl;
607 ofs << fixed << setprecision(13);
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;
616 if(
model.D().cols < 4)
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;
624 ofs <<
"Camera.k3: " << 0.0 << std::endl;
627 if(
model.D().cols >= 4)
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;
634 if(
model.D().cols >= 5)
636 ofs <<
"Camera.k3: " <<
model.D().at<
double>(0,4) << std::endl;
638 if(
model.D().cols > 5)
640 UWARN(
"Unhandled camera distortion size %d, only 5 first coefficients used",
model.D().cols);
644 ofs <<
"Camera.width: " <<
model.imageWidth() << std::endl;
645 ofs <<
"Camera.height: " <<
model.imageHeight() << std::endl;
651 baseline = rtabmap::Parameters::defaultOdomORBSLAMBf();
659 ofs <<
"Camera.RGB: 1" << std::endl;
662 float fps = rtabmap::Parameters::defaultOdomORBSLAMFps();
664 ofs <<
"Camera.fps: " << fps << std::endl;
668 double thDepth = rtabmap::Parameters::defaultOdomORBSLAMThDepth();
670 ofs <<
"ThDepth: " << thDepth << std::endl;
674 ofs <<
"DepthMapFactor: " << 1000.0 << std::endl;
681 int features = rtabmap::Parameters::defaultOdomORBSLAMMaxFeatures();
683 ofs <<
"ORBextractor.nFeatures: " << features << std::endl;
687 double scaleFactor = rtabmap::Parameters::defaultORBScaleFactor();
689 ofs <<
"ORBextractor.scaleFactor: " << scaleFactor << std::endl;
693 int levels = rtabmap::Parameters::defaultORBNLevels();
695 ofs <<
"ORBextractor.nLevels: " << levels << std::endl;
702 int iniThFAST = rtabmap::Parameters::defaultFASTThreshold();
703 int minThFAST = rtabmap::Parameters::defaultFASTMinThreshold();
706 ofs <<
"ORBextractor.iniThFAST: " << iniThFAST << std::endl;
707 ofs <<
"ORBextractor.minThFAST: " << minThFAST << std::endl;
710 int maxFeatureMapSize = rtabmap::Parameters::defaultOdomORBSLAMMapSize();
716 mpKeyFrameDatabase =
new KeyFrameDatabase(*mpVocabulary);
719 mpMap =
new ORB_SLAM2::Map();
723 mpTracker =
new Tracker(0, mpVocabulary, 0, 0, mpMap, mpKeyFrameDatabase, configPath, stereo?System::STEREO:System::RGBD, maxFeatureMapSize);
726 mpLocalMapper =
new LocalMapping(mpMap,
false);
729 mpLoopCloser =
new LoopCloser(mpMap, mpKeyFrameDatabase, mpVocabulary,
true);
731 mptLocalMapping =
new thread(&LocalMapping::Run, mpLocalMapper);
732 mptLoopClosing =
new thread(&LoopCloser::RunNoLoop, mpLoopCloser);
735 mpTracker->SetLocalMapper(mpLocalMapper);
736 mpTracker->SetLoopClosing(mpLoopCloser);
737 mpTracker->SetViewer(0);
739 mpLocalMapper->SetTracker(mpTracker);
740 mpLocalMapper->SetLoopCloser(mpLoopCloser);
742 mpLoopCloser->SetTracker(mpTracker);
743 mpLoopCloser->SetLocalMapper(mpLocalMapper);
746 Frame::mbInitialComputations =
true;
751 virtual ~ORBSLAM2System()
761 mpLocalMapper->RequestFinish();
762 mpLoopCloser->RequestFinish();
765 while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA())
771 mptLoopClosing->join();
772 delete mptLoopClosing;
774 mptLocalMapping->join();
775 delete mptLocalMapping;
779 delete mpLocalMapper;
785 delete mpKeyFrameDatabase;
786 mpKeyFrameDatabase=0;
792 ORBVocabulary* mpVocabulary;
795 KeyFrameDatabase* mpKeyFrameDatabase;
806 LocalMapping* mpLocalMapper;
810 LoopCloser* mpLoopCloser;
814 std::thread* mptLocalMapping;
815 std::thread* mptLoopClosing;
825 #
if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
832 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
833 orbslam_ =
new ORBSLAM2System(parameters);
839 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
850 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
853 orbslam_->shutdown();
856 originLocalTransform_.setNull();
857 previousPose_.setIdentity();
869 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
872 if(
data.imageRaw().empty() ||
873 data.imageRaw().rows !=
data.depthOrRightRaw().rows ||
874 data.imageRaw().cols !=
data.depthOrRightRaw().cols)
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);
881 if(!((
data.cameraModels().size() == 1 &&
882 data.cameraModels()[0].isValidForReprojection()) ||
883 (
data.stereoCameraModels().size() == 1 &&
884 data.stereoCameraModels()[0].isValidForProjection())))
886 UERROR(
"Invalid camera model!");
890 bool stereo =
data.cameraModels().size() == 0;
893 if(orbslam_->mpTracker == 0)
896 if(!orbslam_->init(
model, stereo,
data.cameraModels().size()==1?0.0f:
data.stereoCameraModels()[0].baseline()))
906 localTransform =
data.stereoCameraModels()[0].localTransform();
907 Tcw = ((Tracker*)orbslam_->mpTracker)->GrabImageStereo(
data.imageRaw(),
data.rightRaw(),
data.stamp());
911 localTransform =
data.cameraModels()[0].localTransform();
913 if(
data.depthRaw().type() == CV_32FC1)
915 depth =
data.depthRaw();
917 else if(
data.depthRaw().type() == CV_16UC1)
921 Tcw = ((Tracker*)orbslam_->mpTracker)->GrabImageRGBD(
data.imageRaw(), depth,
data.stamp());
925 if(orbslam_->mpTracker->mState == Tracking::LOST)
927 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
929 else if(Tcw.cols == 4 && Tcw.rows == 4)
935 if(!localTransform.
isNull())
937 if(originLocalTransform_.isNull())
939 originLocalTransform_ = localTransform;
942 p = originLocalTransform_ *
p.inverse() * localTransform.
inverse();
944 t = previousPoseInv*
p;
951 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
956 float baseline =
data.cameraModels().size()==1?0.0f:
data.stereoCameraModels()[0].baseline();
959 baseline = rtabmap::Parameters::defaultOdomORBSLAMBf();
962 double linearVar = 0.0001;
966 linearVar *= linearVar;
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;
979 int totalMapPoints= 0;
983 totalMapPoints = orbslam_->mpMap->MapPointsInMap();
984 totalKfs = orbslam_->mpMap->KeyFramesInMap();
989 info->lost =
t.isNull();
991 info->reg.covariance = covariance;
992 info->localMapSize = totalMapPoints;
993 info->localKeyFrames = totalKfs;
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());
1001 for (
unsigned int i = 0;
i < kpts.size(); ++
i)
1004 if(orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[
i] != 0)
1006 wordId = orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[
i]->mnId;
1012 info->words.insert(std::make_pair(wordId, kpts[
i]));
1013 if(orbslam_->mpTracker->mCurrentFrame.mvpMapPoints[
i] != 0)
1015 info->reg.matchesIDs[oi] = wordId;
1016 info->reg.inliersIDs[oi] = wordId;
1020 info->reg.matchesIDs.resize(oi);
1021 info->reg.inliersIDs.resize(oi);
1022 info->reg.inliers = oi;
1023 info->reg.matches = oi;
1025 std::vector<MapPoint*> mapPoints = orbslam_->mpMap->GetAllMapPoints();
1027 for (
unsigned int i = 0;
i < mapPoints.size(); ++
i)
1029 cv::Point3f pt(mapPoints[
i]->GetWorldPos());
1031 info->localMap.insert(std::make_pair(mapPoints[
i]->mnId, cv::Point3f(ptt.x, ptt.y, ptt.z)));
1036 UINFO(
"Odom update time = %fs, map points=%d, keyframes=%d, lost=%s",
timer.
elapsed(), totalMapPoints, totalKfs,
t.isNull()?
"true":
"false");
1039 UERROR(
"RTAB-Map is not built with ORB_SLAM support! Select another visual odometry approach.");