36 #include <pcl/common/transforms.h> 38 #ifdef RTABMAP_ORB_SLAM2 46 class Tracker:
public Tracking
49 Tracker(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap,
50 KeyFrameDatabase* pKFDB,
const std::string &strSettingPath,
const int sensor,
long unsigned int maxFeatureMapSize) :
51 Tracking(pSys, pVoc, pFrameDrawer, pMapDrawer, pMap, pKFDB, strSettingPath, sensor),
52 maxFeatureMapSize_(maxFeatureMapSize)
57 long unsigned int maxFeatureMapSize_;
62 if(mState==NO_IMAGES_YET)
64 mState = NOT_INITIALIZED;
67 mLastProcessedState=mState;
70 unique_lock<mutex> lock(mpMap->mMutexMapUpdate);
72 if(mState==NOT_INITIALIZED)
75 StereoInitialization();
95 if(mState==OK || mState==LOST)
98 CheckReplacedInLastFrame();
100 if(mVelocity.empty() || mCurrentFrame.mnId<mnLastRelocFrameId+2)
102 bOK = TrackReferenceKeyFrame();
106 bOK = TrackWithMotionModel();
108 bOK = TrackReferenceKeyFrame();
117 bOK = Relocalization();
126 bOK = Relocalization();
134 if(!mVelocity.empty())
136 bOK = TrackWithMotionModel();
140 bOK = TrackReferenceKeyFrame();
152 bool bOKReloc =
false;
153 std::vector<MapPoint*> vpMPsMM;
154 std::vector<bool> vbOutMM;
156 if(!mVelocity.empty())
158 bOKMM = TrackWithMotionModel();
159 vpMPsMM = mCurrentFrame.mvpMapPoints;
160 vbOutMM = mCurrentFrame.mvbOutlier;
161 TcwMM = mCurrentFrame.mTcw.clone();
163 bOKReloc = Relocalization();
165 if(bOKMM && !bOKReloc)
167 mCurrentFrame.SetPose(TcwMM);
168 mCurrentFrame.mvpMapPoints = vpMPsMM;
169 mCurrentFrame.mvbOutlier = vbOutMM;
173 for(
int i =0; i<mCurrentFrame.N; i++)
175 if(mCurrentFrame.mvpMapPoints[i] && !mCurrentFrame.mvbOutlier[i])
177 mCurrentFrame.mvpMapPoints[i]->IncreaseFound();
187 bOK = bOKReloc || bOKMM;
192 mCurrentFrame.mpReferenceKF = mpReferenceKF;
198 bOK = TrackLocalMap();
206 bOK = TrackLocalMap();
221 if(!mLastFrame.mTcw.empty())
223 cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F);
224 mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3));
225 mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3));
226 mVelocity = mCurrentFrame.mTcw*LastTwc;
229 mVelocity = cv::Mat();
234 for(
int i=0; i<mCurrentFrame.N; i++)
236 MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];
238 if(pMP->Observations()<1)
240 mCurrentFrame.mvbOutlier[i] =
false;
241 mCurrentFrame.mvpMapPoints[i]=
static_cast<MapPoint*
>(
NULL);
246 for(list<MapPoint*>::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++)
248 MapPoint* pMP = *lit;
251 mlpTemporalPoints.clear();
254 if(NeedNewKeyFrame())
259 if(maxFeatureMapSize_ > 0)
262 if(mpMap->KeyFramesInMap()>1 && mpMap->MapPointsInMap()>maxFeatureMapSize_)
264 std::vector<KeyFrame*> kfs = mpMap->GetAllKeyFrames();
265 std::map<long unsigned int, KeyFrame*> kfsSorted;
266 for(
unsigned int i=1; i<kfs.size(); ++i)
268 kfsSorted.insert(std::make_pair(kfs[i]->mnId, kfs[i]));
270 KeyFrame * lastFrame = kfsSorted.rbegin()->second;
271 std::vector<MapPoint*> mapPoints = mpMap->GetAllMapPoints();
272 std::map<long unsigned int, MapPoint*> mapPointsSorted;
273 for(
unsigned int i=0; i<mapPoints.size(); ++i)
275 mapPointsSorted.insert(std::make_pair(mapPoints[i]->mnId, mapPoints[i]));
278 for(std::map<long unsigned int, MapPoint*>::iterator iter=mapPointsSorted.begin();
279 iter != mapPointsSorted.end() && mpMap->MapPointsInMap()>maxFeatureMapSize_;
282 if(!iter->second->IsInKeyFrame(lastFrame))
287 iter->second->SetBadFlag();
291 for(std::map<long unsigned int, KeyFrame*>::iterator iter=kfsSorted.begin();
292 iter != kfsSorted.end();
295 if(iter->second!=lastFrame && iter->second->GetMapPoints().size()==0)
300 iter->second->SetErase();
314 for(
int i=0; i<mCurrentFrame.N;i++)
316 if(mCurrentFrame.mvpMapPoints[i] && mCurrentFrame.mvbOutlier[i])
317 mCurrentFrame.mvpMapPoints[i]=
static_cast<MapPoint*
>(
NULL);
326 UWARN(
"Track lost...");
332 if(!mCurrentFrame.mpReferenceKF)
333 mCurrentFrame.mpReferenceKF = mpReferenceKF;
335 mLastFrame = Frame(mCurrentFrame);
339 if(!mCurrentFrame.mTcw.empty())
341 cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse();
342 mlRelativeFramePoses.push_back(Tcr);
343 mlpReferences.push_back(mpReferenceKF);
344 mlFrameTimes.push_back(mCurrentFrame.mTimeStamp);
345 mlbLost.push_back(mState==LOST);
350 mlRelativeFramePoses.push_back(mlRelativeFramePoses.back());
351 mlpReferences.push_back(mlpReferences.back());
352 mlFrameTimes.push_back(mlFrameTimes.back());
353 mlbLost.push_back(mState==LOST);
357 void StereoInitialization()
359 if(mCurrentFrame.N>500)
362 mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
365 KeyFrame* pKFini =
new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB);
368 mpMap->AddKeyFrame(pKFini);
371 for(
int i=0; i<mCurrentFrame.N;i++)
373 float z = mCurrentFrame.mvDepth[i];
376 cv::Mat x3D = mCurrentFrame.UnprojectStereo(i);
377 MapPoint* pNewMP =
new MapPoint(x3D,pKFini,mpMap);
378 pNewMP->AddObservation(pKFini,i);
379 pKFini->AddMapPoint(pNewMP,i);
380 pNewMP->ComputeDistinctiveDescriptors();
381 pNewMP->UpdateNormalAndDepth();
382 mpMap->AddMapPoint(pNewMP);
384 mCurrentFrame.mvpMapPoints[i]=pNewMP;
388 cout <<
"New map created with " << mpMap->MapPointsInMap() <<
" points" << endl;
390 mpLocalMapper->InsertKeyFrame(pKFini);
392 mLastFrame = Frame(mCurrentFrame);
393 mnLastKeyFrameId=mCurrentFrame.mnId;
394 mpLastKeyFrame = pKFini;
396 mvpLocalKeyFrames.push_back(pKFini);
397 mvpLocalMapPoints=mpMap->GetAllMapPoints();
398 mpReferenceKF = pKFini;
399 mCurrentFrame.mpReferenceKF = pKFini;
401 mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
403 mpMap->mvpKeyFrameOrigins.push_back(pKFini);
412 cv::Mat GrabImageStereo(
const cv::Mat &imRectLeft,
const cv::Mat &imRectRight,
const double ×tamp)
414 mImGray = imRectLeft;
415 cv::Mat imGrayRight = imRectRight;
417 if(mImGray.channels()==3)
421 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
425 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
428 else if(mImGray.channels()==4)
432 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
436 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
439 if(imGrayRight.channels()==3)
443 cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY);
447 cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY);
450 else if(imGrayRight.channels()==4)
454 cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY);
458 cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY);
462 mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
466 return mCurrentFrame.mTcw.clone();
469 cv::Mat GrabImageRGBD(
const cv::Mat &imRGB,
const cv::Mat &imD,
const double ×tamp)
472 cv::Mat imDepth = imD;
474 if(mImGray.channels()==3)
477 cvtColor(mImGray,mImGray,CV_RGB2GRAY);
479 cvtColor(mImGray,mImGray,CV_BGR2GRAY);
481 else if(mImGray.channels()==4)
484 cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
486 cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
489 UASSERT(imDepth.type()==CV_32F);
491 mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
495 return mCurrentFrame.mTcw.clone();
500 class LoopCloser:
public LoopClosing
503 LoopCloser(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,
const bool bFixScale) :
504 LoopClosing(pMap, pDB, pVoc, bFixScale)
517 unique_lock<mutex> lock(mMutexLoopQueue);
518 mlpLoopKeyFrameQueue.clear();
540 mpKeyFrameDatabase(0),
547 parameters_(parameters)
549 std::string vocabularyPath;
552 if(!vocabularyPath.empty())
556 UWARN(
"Loading ORB Vocabulary: \"%s\". This could take a while...", vocabularyPath.c_str());
557 mpVocabulary =
new ORB_SLAM2::ORBVocabulary();
558 bool bVocLoad = mpVocabulary->loadFromTextFile(vocabularyPath);
561 UERROR(
"Failed to open vocabulary at %s", vocabularyPath.c_str());
567 UWARN(
"Vocabulary loaded!");
572 UERROR(
"ORBSLAM2 vocabulary path should be set! (Parameter name=\"%s\")", rtabmap::Parameters::kOdomORBSLAM2VocPath().c_str());
580 UERROR(
"Vocabulary not loaded!");
587 std::string workingDir;
589 if(workingDir.empty())
593 std::string configPath = workingDir+
"/rtabmap_orbslam2.yaml";
594 std::ofstream ofs (configPath, std::ofstream::out);
595 ofs <<
"%YAML:1.0" << std::endl;
599 ofs <<
"Camera.fx: " << model.
fx() << std::endl;
600 ofs <<
"Camera.fy: " << model.
fy() << std::endl;
601 ofs <<
"Camera.cx: " << model.
cx() << std::endl;
602 ofs <<
"Camera.cy: " << model.
cy() << std::endl;
605 if(model.
D().cols < 4)
607 ofs <<
"Camera.k1: " << 0 << std::endl;
608 ofs <<
"Camera.k2: " << 0 << std::endl;
609 ofs <<
"Camera.p1: " << 0 << std::endl;
610 ofs <<
"Camera.p2: " << 0 << std::endl;
613 ofs <<
"Camera.k3: " << 0 << std::endl;
616 if(model.
D().cols >= 4)
618 ofs <<
"Camera.k1: " << model.
D().at<
double>(0,0) << std::endl;
619 ofs <<
"Camera.k2: " << model.
D().at<
double>(0,1) << std::endl;
620 ofs <<
"Camera.p1: " << model.
D().at<
double>(0,2) << std::endl;
621 ofs <<
"Camera.p2: " << model.
D().at<
double>(0,3) << std::endl;
623 if(model.
D().cols >= 5)
625 ofs <<
"Camera.k3: " << model.
D().at<
double>(0,4) << std::endl;
627 if(model.
D().cols > 5)
629 UWARN(
"Unhandled camera distortion size %d, only 5 first coefficients used", model.
D().cols);
633 ofs <<
"Camera.width: " << model.
imageWidth() << std::endl;
634 ofs <<
"Camera.height: " << model.
imageHeight() << std::endl;
640 baseline = rtabmap::Parameters::defaultOdomORBSLAM2Bf();
643 ofs <<
"Camera.bf: " << model.
fx()*baseline << std::endl;
648 ofs <<
"Camera.RGB: 1" << std::endl;
651 float fps = rtabmap::Parameters::defaultOdomORBSLAM2Fps();
653 ofs <<
"Camera.fps: " << fps << std::endl;
657 double thDepth = rtabmap::Parameters::defaultOdomORBSLAM2ThDepth();
659 ofs <<
"ThDepth: " << thDepth << std::endl;
663 ofs <<
"DepthMapFactor: " << 1000.0 << std::endl;
670 int features = rtabmap::Parameters::defaultOdomORBSLAM2MaxFeatures();
672 ofs <<
"ORBextractor.nFeatures: " << features << std::endl;
676 double scaleFactor = rtabmap::Parameters::defaultORBScaleFactor();
678 ofs <<
"ORBextractor.scaleFactor: " << scaleFactor << std::endl;
682 int levels = rtabmap::Parameters::defaultORBNLevels();
684 ofs <<
"ORBextractor.nLevels: " << levels << std::endl;
691 int iniThFAST = rtabmap::Parameters::defaultFASTThreshold();
692 int minThFAST = rtabmap::Parameters::defaultFASTMinThreshold();
695 ofs <<
"ORBextractor.iniThFAST: " << iniThFAST << std::endl;
696 ofs <<
"ORBextractor.minThFAST: " << minThFAST << std::endl;
699 int maxFeatureMapSize = rtabmap::Parameters::defaultOdomORBSLAM2MapSize();
705 mpKeyFrameDatabase =
new ORB_SLAM2::KeyFrameDatabase(*mpVocabulary);
708 mpMap =
new ORB_SLAM2::Map();
712 mpTracker =
new ORB_SLAM2::Tracker(0, mpVocabulary, 0, 0, mpMap, mpKeyFrameDatabase, configPath, stereo?ORB_SLAM2::System::STEREO:ORB_SLAM2::System::RGBD, maxFeatureMapSize);
715 mpLocalMapper =
new ORB_SLAM2::LocalMapping(mpMap,
false);
718 mpLoopCloser =
new ORB_SLAM2::LoopCloser(mpMap, mpKeyFrameDatabase, mpVocabulary,
true);
720 mptLocalMapping =
new thread(&ORB_SLAM2::LocalMapping::Run, mpLocalMapper);
721 mptLoopClosing =
new thread(&ORB_SLAM2::LoopCloser::RunNoLoop, mpLoopCloser);
724 mpTracker->SetLocalMapper(mpLocalMapper);
725 mpTracker->SetLoopClosing(mpLoopCloser);
726 mpTracker->SetViewer(0);
728 mpLocalMapper->SetTracker(mpTracker);
729 mpLocalMapper->SetLoopCloser(mpLoopCloser);
731 mpLoopCloser->SetTracker(mpTracker);
732 mpLoopCloser->SetLocalMapper(mpLocalMapper);
737 virtual ~ORBSLAM2System()
747 mpLocalMapper->RequestFinish();
748 mpLoopCloser->RequestFinish();
751 while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA())
757 mptLoopClosing->join();
758 delete mptLoopClosing;
760 mptLocalMapping->join();
761 delete mptLocalMapping;
765 delete mpLocalMapper;
771 delete mpKeyFrameDatabase;
772 mpKeyFrameDatabase=0;
778 ORB_SLAM2::ORBVocabulary* mpVocabulary;
781 ORB_SLAM2::KeyFrameDatabase* mpKeyFrameDatabase;
784 ORB_SLAM2::Map* mpMap;
789 ORB_SLAM2::Tracker* mpTracker;
792 ORB_SLAM2::LocalMapping* mpLocalMapper;
796 ORB_SLAM2::LoopCloser* mpLoopCloser;
800 std::thread* mptLocalMapping;
801 std::thread* mptLoopClosing;
811 #ifdef RTABMAP_ORB_SLAM2
818 #ifdef RTABMAP_ORB_SLAM2 819 orbslam2_ =
new ORBSLAM2System(parameters);
825 #ifdef RTABMAP_ORB_SLAM2 836 #ifdef RTABMAP_ORB_SLAM2 839 orbslam2_->shutdown();
842 originLocalTransform_.setNull();
843 previousPose_.setIdentity();
855 #ifdef RTABMAP_ORB_SLAM2 862 UERROR(
"Not supported input! RGB (%dx%d) and depth (%dx%d) should have the same size.",
873 UERROR(
"Invalid camera model!");
880 if(orbslam2_->mpTracker == 0)
894 Tcw = ((ORB_SLAM2::Tracker*)orbslam2_->mpTracker)->GrabImageStereo(data.
imageRaw(), data.
rightRaw(), data.
stamp());
898 localTransform = data.
cameraModels()[0].localTransform();
900 if(data.
depthRaw().type() == CV_32FC1)
904 else if(data.
depthRaw().type() == CV_16UC1)
908 Tcw = ((ORB_SLAM2::Tracker*)orbslam2_->mpTracker)->GrabImageRGBD(data.
imageRaw(), depth, data.
stamp());
912 if(orbslam2_->mpTracker->mState == ORB_SLAM2::Tracking::LOST)
914 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
916 else if(Tcw.cols == 4 && Tcw.rows == 4)
922 if(!localTransform.
isNull())
924 if(originLocalTransform_.isNull())
926 originLocalTransform_ = localTransform;
929 p = originLocalTransform_ * p.
inverse() * localTransform.
inverse();
931 t = previousPoseInv*p;
938 covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0f;
946 baseline = rtabmap::Parameters::defaultOdomORBSLAM2Bf();
949 double linearVar = 0.0001;
952 linearVar = baseline/8.0;
953 linearVar *= linearVar;
956 covariance = cv::Mat::eye(6,6, CV_64FC1);
957 covariance.at<
double>(0,0) = linearVar;
958 covariance.at<
double>(1,1) = linearVar;
959 covariance.at<
double>(2,2) = linearVar;
960 covariance.at<
double>(3,3) = 0.0001;
961 covariance.at<
double>(4,4) = 0.0001;
962 covariance.at<
double>(5,5) = 0.0001;
966 int totalMapPoints= 0;
970 totalMapPoints = orbslam2_->mpMap->MapPointsInMap();
971 totalKfs = orbslam2_->mpMap->KeyFramesInMap();
984 const std::vector<cv::KeyPoint> & kpts = orbslam2_->mpTracker->mCurrentFrame.mvKeys;
988 for (
unsigned int i = 0; i < kpts.size(); ++i)
991 if(orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
993 wordId = orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i]->mnId;
999 info->
words.insert(std::make_pair(wordId, kpts[i]));
1000 if(orbslam2_->mpTracker->mCurrentFrame.mvpMapPoints[i] != 0)
1012 std::vector<ORB_SLAM2::MapPoint*> mapPoints = orbslam2_->mpMap->GetAllMapPoints();
1013 Eigen::Affine3f fixRot = (this->
getPose()*previousPoseInv*originLocalTransform_).toEigen3f();
1014 for (
unsigned int i = 0; i < mapPoints.size(); ++i)
1016 cv::Point3f pt(mapPoints[i]->GetWorldPos());
1018 info->
localMap.insert(std::make_pair(mapPoints[i]->mnId, cv::Point3f(ptt.x, ptt.y, ptt.z)));
1023 UINFO(
"Odom update time = %fs, map points=%d, keyframes=%d, lost=%s", timer.
elapsed(), totalMapPoints, totalKfs, t.
isNull()?
"true":
"false");
1026 UERROR(
"RTAB-Map is not built with ORB_SLAM2 support! Select another visual odometry approach.");
static std::string homeDir()
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat &depth16U)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
bool isInfoDataFilled() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
virtual void reset(const Transform &initialPose=Transform::getIdentity())
std::map< int, cv::Point3f > localMap
std::map< std::string, std::string > ParametersMap
virtual ~OdometryORBSLAM2()
const Transform & getPose() const
std::vector< int > inliersIDs
const cv::Mat & imageRaw() const
#define UASSERT(condition)
Wrappers of STL for convenient functions.
bool isValidForProjection() const
const CameraModel & left() const
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
const cv::Mat & depthOrRightRaw() const
bool isValidForReprojection() const
const std::vector< CameraModel > & cameraModels() const
std::multimap< int, cv::KeyPoint > words
const CameraModel & right() const
ROSCONSOLE_DECL void shutdown()
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
std::vector< int > matchesIDs
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
const Transform & localTransform() const