Inspecting differences in performance between `raulmur/ORBSLAM2` and `jingpang/LearnVIORB`
The canonical implementation of ORB-SLAM2 by Raúl Mur-Artal seems to perform better than the (non-visual-inertial) binaries generated by the code of Jing Wang. I’m looking into why, so Wang’s code can be improved, and perhaps some bugs for the stereo case may be squashed.
The situation
Both repositories can generate executables that test the mono and stereo implementations on the EuRoC dataset. These executables are mono_euroc
and stereo_euroc
, respectively for monocular and stereo vision datasets. Given the same settings and dataset, the binaries of Wang should demonstrate comparable behavior to the ones of Mur-Artal. This is not the case.
In the tests below, EuRoC V1-02 has been used. The configuration file for Mur-Artal’s code can be found in ORB_SLAM2/Examples/{Monocular,Stereo}/EuRoC.yaml
. The configuration file for Wang’s code is located in LearnVIORB/config/euroc.yaml
, extended with the missing fields from the ORB_SLAM2
config file. The vocabulary used is ORB_SLAM2/Vocabulary/ORBvoc.txt
for both; Wang packed a binary version of the vocabulary with their code, which loads faster. However, Mur-Artal’s version does not support loading that binary. Just to be sure that there is no difference between the two vocabularies, I have used the text-version.
I have compared the most recent commit of LearnVIOS
to the most recent commit of ORB_SLAM2
.
Problem
Wang’s binaries show multiple differences in behavior:
- When localization is lost, the complete map is thrown away.
mono_euroc
loses localization at aroungt = ~26s
, and never relocalizes.stereo_euroc
doesn’t localize until the drone lifts off (while it should be able to do that), and att = ~26s
loses localization again. Relocalizing seems to trigger a segmentation fault.- The number of generated keyframes is much higher in Wang’s version than in Mur-Artal’s version.
- The older keyframes seem to shift in pose a lot more than in Mur-Artal’s.
Approach in finding the problems
I will first identify the differences in the files, and inspect each. Then I will merge the most recent commit of ORB_SLAM2
into LearnVIOS
. Then I will inspect if there are any changes in behavior. Then I will again run a diff
along the two repos.
Differences in implementation
As noted above, Wang’s code can load binary and plain-text files for the vocabulary, while Mur-Artal can only load plain-text files. To eliminate any differences, I fed them both the plain-text vocabulary that was packaged with Mur-Artal’s code.
Configuration files
There were small differences and missing parameters in the configuration file of LearnVIOS
. Where ORB_SLAM2
’s config has the same parameters, I have used those.
C++ files
In all files, std::map<KeyFrame*, size_t>
has been replaced with mapMapPointObs = std::map<KeyFrame*,size_t,cmpKeyFrameId>
; bool cmpKeyFrameId(KeyFrame* a, KeyFrame* b)
compares the mnId
fields of both KeyFrame
s, so that the map can be sorted.
The following C++ classes, functions and types from LearnVIORB
are changed wrt the ORB_SLAM2
repository (let’s assume I’m using namespace ORB_SLAM2;
for brevity and readability):
Converter
implements some functionality to update theNavState
(new inLearnVIORB
) throughstatic void Converter::updateNS(NavState& ns, const IMUPreintegrator& imupreint, const Vector3d& gw)
. It also has astatic cv::Mat Converter::toCvMatInverse(const cv::Mat &T12)
.Frame
has some additions. Firstly, the data members:public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW //... // IMU Data from last Frame to this Frame std::vector<IMUData> mvIMUDataSinceLastFrame; // For pose optimization, use as prior and prior information(inverse covariance) Matrix<double,15,15> mMargCovInv; NavState mNavStatePrior; protected: NavState mNavState; // ...
Because it now stores a fixed-size vectorizable Eigen type, it has to have
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
.It also has a few extra functions, with self-explanatory names:
public: Frame(const cv::Mat &imGray, const double &timeStamp, const std::vector<IMUData> &vimu, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, KeyFrame* pLastKF=NULL); void ComputeIMUPreIntSinceLastFrame(const Frame* pLastF, IMUPreintegrator& imupreint) const; void UpdatePoseFromNS(const cv::Mat &Tbc); void SetInitialNavStateAndBias(const NavState& ns); void UpdateNavState(const IMUPreintegrator& imupreint, const Vector3d& gw); const NavState& GetNavState(void) const; void SetNavState(const NavState& ns); void SetNavStateBiasGyr(const Vector3d &bg); void SetNavStateBiasAcc(const Vector3d &ba);
Its copy constructor
Frame::Frame(const Frame& f)
sets the new data members appropriately to copies off
.KeyFrame
also has a lot of data additions:public: // Variables used by loop closing NavState mNavStateGBA; //mTcwGBA NavState mNavStateBefGBA; //mTcwBefGBA protected: std::mutex mMutexPrevKF; std::mutex mMutexNextKF; KeyFrame* mpPrevKeyFrame; KeyFrame* mpNextKeyFrame; // P, V, R, bg, ba, delta_bg, delta_ba (delta_bx is for optimization update) std::mutex mMutexNavState; NavState mNavState; // IMU Data from lask KeyFrame to this KeyFrame std::mutex mMutexIMUData; std::vector<IMUData> mvIMUData; IMUPreintegrator mIMUPreInt;
It has
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
, but I don’t think it should have that.It adds the following function members:
public: KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB, std::vector<IMUData> vIMUData, KeyFrame* pLastKF=NULL); KeyFrame* GetPrevKeyFrame(void); KeyFrame* GetNextKeyFrame(void); void SetPrevKeyFrame(KeyFrame* pKF); void SetNextKeyFrame(KeyFrame* pKF); // std::vector<IMUData> GetVectorIMUData(void); void AppendIMUDataToFront(KeyFrame* pPrevKF); void ComputePreInt(void); // const IMUPreintegrator & GetIMUPreInt(void); // void UpdateNavStatePVRFromTcw(const cv::Mat &Tcw,const cv::Mat &Tbc); void UpdatePoseFromNS(const cv::Mat &Tbc); void UpdateNavState(const IMUPreintegrator& imupreint, const Vector3d& gw); void SetNavState(const NavState& ns); const NavState& GetNavState(void); void SetNavStateVel(const Vector3d &vel); void SetNavStatePos(const Vector3d &pos); void SetNavStateRot(const Matrix3d &rot); void SetNavStateRot(const Sophus::SO3 &rot); void SetNavStateBiasGyr(const Vector3d &bg); void SetNavStateBiasAcc(const Vector3d &ba); void SetNavStateDeltaBg(const Vector3d &dbg); void SetNavStateDeltaBa(const Vector3d &dba); // void SetInitialNavStateAndBias(const NavState& ns);
Effectively, KeyFrame is now a node in a linked list of KeyFrames.
In the constructor
KeyFrame::KeyFrame(Frame &F, Map *pMap, KeyFrameDatabase *pKFDB)
, it setsmpPrevKeyFrame
andmpNextKeyFrame
toNULL
. The other members are set by default to sensible values.LocalMapping
adds the following members:public: ConfigParam* mpParams; // // KeyFrames in Local Window, for Local BA // Insert in ProcessNewKeyFrame() void AddToLocalWindow(KeyFrame* pKF); void DeleteBadInLocalWindow(void); // void VINSInitThread(void); bool TryInitVIO(void); bool GetVINSInited(void); void SetVINSInited(bool flag); // bool GetFirstVINSInited(void); void SetFirstVINSInited(bool flag); // cv::Mat GetGravityVec(void); cv::Mat GetRwiInit(void); // bool GetMapUpdateFlagForTracking(); void SetMapUpdateFlagInTracking(bool bflag); KeyFrame* GetMapUpdateKF(); // const KeyFrame* GetCurrentKF(void) const {return mpCurrentKeyFrame;} // std::mutex mMutexUpdatingInitPoses; bool GetUpdatingInitPoses(void); void SetUpdatingInitPoses(bool flag); // std::mutex mMutexInitGBAFinish; bool mbInitGBAFinish; bool GetFlagInitGBAFinish() { unique_lock<mutex> lock(mMutexInitGBAFinish); return mbInitGBAFinish; } void SetFlagInitGBAFinish(bool flag) { unique_lock<mutex> lock(mMutexInitGBAFinish); mbInitGBAFinish = flag; } // protected: double mnStartTime; bool mbFirstTry; double mnVINSInitScale; cv::Mat mGravityVec; // gravity vector in world frame cv::Mat mRwiInit; // std::mutex mMutexVINSInitFlag; bool mbVINSInited; // std::mutex mMutexFirstVINSInitFlag; bool mbFirstVINSInited; // unsigned int mnLocalWindowSize; std::list<KeyFrame*> mlLocalKeyFrames; // std::mutex mMutexMapUpdateFlag; bool mbMapUpdateFlagForTracking; KeyFrame* mpMapUpdateKF; // bool mbUpdatingInitPoses; // std::mutex mMutexCopyInitKFs; bool mbCopyInitKFs; bool GetFlagCopyInitKFs() { unique_lock<mutex> lock(mMutexCopyInitKFs); return mbCopyInitKFs; } void SetFlagCopyInitKFs(bool flag) { unique_lock<mutex> lock(mMutexCopyInitKFs); mbCopyInitKFs = flag; }
The constructor
LocalMapping::LocalMapping(Map* pMap, const float bMonocular, ConfigParam* pParams);
has now that thirdConfigParam*
argument. It setsmpParams
,mnLocalWindowSize
,mbVINSInited
,mbFirstTry
,mbFirstVINSInited
,mbUpdatingInitPoses
,mbCopyInitKFs
, andmbInitGBAFinish
; the others are set by default to sensible values.In
LocalMapping::Run()
, a few changes are made:- l.958-987: if the Visual Inertial Navigation System (VINS) is not initialized, use
Optimizer::LocalBundleAdjustment(...)
, as in the original version. If VINS is initialized, useOptimizer::LocalBAPRVIDP(...)
. After that, it checks if the program should not run in real-time (but, for example, from a ROS bag). If it shouldn’t and the VINS is not initialized, it initializes the VINS. - l.994-995: instead of always inserting a
KeyFrame
at this point, it only inserts if the VINS is initialized (ifmbInitGBAFinish == true
).
In
LocalMapping::ProcessNewKeyFrame()
, „bad KeyFrames” (we might find out what that means later?) are deleted from the local window, and the current keyframe is added to the local window.In
LocalMapping::KeyFrameCulling()
:- l.1547-1554 & l.1657: KeyFrames are only culled once when
!ConfigParam::GetRealTimeFlags()
or when!mbCopyInitKFs
. That last variable is only set tofalse
when running this function, or a portion ofLocalMapping::TryInitVIO()
; afterwards, it is set totrue
again. This works kind of like a mutex, but doesn’t let other processes queue up on it. - l.1561-1604: In the for-loop that actually culls the KeyFrames, the linked list of KeyFrames is inspected. A KeyFrame
k
is deleted under the following conditions:- If
k
is neither the first or last node, and the VINS is not initialized, and there is more than 0.5s betweenk
’s previous and next KeyFrame - If
k
’s next KeyFrame is thempCurrentKeyFrame
- If
k
is at least 0.11s older thanmpCurrentKeyFrame
- If
k
s previous and next KeyFrames have less thantimegap
time between them. If the VINS is initialized and the previous KeyFrame is more than 4.0s older thank
,timegap = 3.01
. Else,timegap = 0.51
.
- If
In
LocalMapping::ResetIfRequested()
,mlLocalKeyFrames
,mbVINSInited
andmbFirstTry
are reset to initial values.- l.958-987: if the Visual Inertial Navigation System (VINS) is not initialized, use
LoopClosing
includes the following extra members:public: ConfigParam* mpParams; // bool GetMapUpdateFlagForTracking(); void SetMapUpdateFlagInTracking(bool bflag); protected: std::mutex mMutexMapUpdateFlag; bool mbMapUpdateFlagForTracking;
Its only constructor
LoopClosing::LoopClosing(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale, ConfigParam* pParams)
now takes a finalConfigParam*
argument.mpParams
is set accordingly here.Also,
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
is removed, as no fixed-size vectorizable Eigen object is stored, and never has been.In
LoopClosure::Run()
, an extra check (at l.87) is added to correct a loop: this will now only happen when VINS is initialized.In
LoopClosure::CorrectLoop()
on l.593, a flag of updating the map is set on theLoopClosure
object, instead of theMap
object. This probably stems fromLearnVIORB
being forked earlier thanORB_SLAM2
having that feature.In
LoopClosure::RunGlobalBundleAdjustment()
on l.678,Optimizer::GlobalBundleAdjustemnt
is replaced with a VIORB-specificGlobalBundleAdjustmentNavStatePRV
. On l.701, l.723-733 & l.739-742, code is added to correct the position $p$, velocity $v$ and orientation $R$ of the keyframe to fit the VI-ORBSLAM paper.-
MapDrawer
uses a different color for the current camera. -
Map
adds avoid UpdateScale(const double& scale)
method. It is missing theInformNewBigChange()
,GetLastBigChange()
andint mnBigChangeIdx
members. This difference is probably to be attributed toLearnVIORB
to be forked earlier fromORB_SLAM2
than when this was implemented. This functionality has been implemented inLoopClosing
. -
MapPoint
also has avoid UpdateScale(float scale)
method (probably a typo to usefloat
instead ofdouble
).In l.139-148,
MapPoint::EraseObservation
searches for apKFrefnew
; the first KeyFrame inmObservations
(a map that connects KeyFrames observing the MapPoint, and the MapPoint’s associated index in the KeyFrame) that!isBad()
, and set it as its reference KeyFramempRefKF
. If there is no such KeyFrame, this MapPoint isbBad = true
. Optimizer
is changed in the following ways:- It has some new members:
public: void static LocalBAPRVIDP(KeyFrame *pKF, const std::list<KeyFrame*> &lLocalKeyFrames, bool* pbStopFlag, Map* pMap, cv::Mat& gw, LocalMapping* pLM=NULL); // void static GlobalBundleAdjustmentNavStatePRV(Map* pMap, const cv::Mat& gw, int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust); void static LocalBundleAdjustmentNavStatePRV(KeyFrame *pKF, const std::list<KeyFrame*> &lLocalKeyFrames, bool* pbStopFlag, Map* pMap, cv::Mat& gw, LocalMapping* pLM=NULL); // void static GlobalBundleAdjustmentNavState(Map* pMap, const cv::Mat& gw, int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust); // int static PoseOptimization(Frame *pFrame, KeyFrame* pLastKF, const IMUPreintegrator& imupreint, const cv::Mat& gw, const bool& bComputeMarg=false); int static PoseOptimization(Frame *pFrame, Frame* pLastFrame, const IMUPreintegrator& imupreint, const cv::Mat& gw, const bool& bComputeMarg=false); // void static LocalBundleAdjustmentNavState(KeyFrame *pKF, const std::list<KeyFrame*> &lLocalKeyFrames, bool* pbStopFlag, Map* pMap, cv::Mat& gw, LocalMapping* pLM=NULL); // Vector3d static OptimizeInitialGyroBias(const std::list<KeyFrame*> &lLocalKeyFrames); Vector3d static OptimizeInitialGyroBias(const std::vector<KeyFrame*> &vLocalKeyFrames); Vector3d static OptimizeInitialGyroBias(const std::vector<Frame> &vFrames); Vector3d static OptimizeInitialGyroBias(const vector<cv::Mat>& vTwc, const vector<IMUPreintegrator>& vImuPreInt); // void static LocalBundleAdjustment(KeyFrame *pKF, const std::list<KeyFrame*> &lLocalKeyFrames, bool* pbStopFlag, Map* pMap, LocalMapping* pLM=NULL);
Optimizer::PoseOptimization(Frame *pFrame)
uses ag2o::LinearSolverCholmod
instead ofg2o::LinearSolverDense
.Optimizer::LocalBundleAdjustment(...)
now takes a pointer to theLocalMapper
as final argument. At the end of the function, on l.4087-4090, it lets theLocalMapper
know if the map has been changed.Optimizer::OptimizeEssentialGraph(...)
takes a pointer to theLoopCloser
as final argument. At the end of the function, on l.4364-4367, it lets theLoopCloser
know if the map has been changed. Also, on l.4328, it updates the position $p$, velocity $v$ and orientation $R$ for each KeyFrame.
- It has some new members:
System
has several changes in its interface, and implementation.- Let’s start with what is missing:
public: // Returns true if there have been a big map change (loop closure, global BA) // since last call to this function bool MapChanged(); // Information from most recent processed frame // You can call this right after TrackMonocular (or stereo or RGBD) int GetTrackingState(); std::vector<MapPoint*> GetTrackedMapPoints(); std::vector<cv::KeyPoint> GetTrackedKeyPointsUn(); private: // Tracking state int mTrackingState; std::vector<MapPoint*> mTrackedMapPoints; std::vector<cv::KeyPoint> mTrackedKeyPointsUn; std::mutex mMutexState;
Again, this is due to the forked version being behind on the original repository.
- Other members are added:
public: bool bLocalMapAcceptKF(void); void SaveKeyFrameTrajectoryNavState(const string& filename); cv::Mat TrackMonoVI(const cv::Mat &im, const std::vector<IMUData> &vimu, const double ×tamp); private: std::thread* mptLocalMappingVIOInit;
- In the constructor (which now also accepts a
ConfigParam*
as final argument) we see on l.184-188 that this version can parse the binary format for the DBoW2 engine. Also, on l.223-227,mpViewer
is still set with a buggy, old version of the original code. System::TrackStereo(...)
on l.288,System::TrackRGBD(...)
on l.333, andSystem::TrackMonocular(...)
on l.378 miss out on an upstream bugfix.- In
System::Shutdown()
,mpViewer
is not properly ended; no check to see if the pointer is notnull
is performed.
- Let’s start with what is missing:
Tracking
has the following changes:- It adds the following members:
public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW // // Flags for relocalization. Create new KF once bias re-computed & flag for preparation for bias re-compute bool mbCreateNewKFAfterReloc; bool mbRelocBiasPrepare; void RecomputeIMUBiasAndCurrentNavstate(NavState& nscur); // 20 Frames are used to compute bias vector<Frame> mv20FramesReloc; // // Predict the NavState of Current Frame by IMU void PredictNavStateByIMU(bool bMapUpdated); IMUPreintegrator mIMUPreIntInTrack; // bool TrackWithIMU(bool bMapUpdated=false); bool TrackLocalMapWithIMU(bool bMapUpdated=false); // ConfigParam* mpParams; cv::Mat GrabImageMonoVI(const cv::Mat &im, const std::vector<IMUData> &vimu, const double ×tamp); // IMU Data since last KF. Append when new data is provided // Should be cleared in 1. initialization beginning, 2. new keyframe created. std::vector<IMUData> mvIMUSinceLastKF; IMUPreintegrator GetIMUPreIntSinceLastKF(Frame* pCurF, KeyFrame* pLastKF, const std::vector<IMUData>& vIMUSInceLastKF); IMUPreintegrator GetIMUPreIntSinceLastFrame(Frame* pCurF, Frame* pLastF);
The
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
does not make a lot of sense, but I guess it doesn’t do any harm. - The only constructor
Tracking::Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, ConfigParam* pParams)
accepts a finalConfigParam*
argument, and sets the new fields sensibly. Tracking::Track()
has been modified in the following ways:- On the top of the file, a macro
TRACK_WITH_IMU
is defined. We will see later that the code checks if it exists; if it doesn’t, it falls back to the behavior ofORB_SLAM2
. - On l.736-751, it checks if there has been a map update according to its
mpLocalMapper
member,mpLoopClosing
member, or becausemCurrentFrame.mnId == mnLastRelocFrameId + 20
. If so, we setbMapUpdated = true
. - On l.781-812, originally checked if
mVelocity.empty() || mCurrentFrame.mnId < mnLastRelocFrameId+2
. If so, setbOK = TrackReferenceKeyFrame()
or else try tobOK = TrackWithMotionModel()
; ifbOK == false
, still useTrackReferenceKeyFrame()
. This is now prefaced with anotherif
whenTRACK_WITH_IMU
is defined. If the VINS is initialized, it tracks with only vision ifTracking::Relocalization()
returnedtrue
previously. Otherwise (still with an initialized VINS), the program tries toTrackWithIMU(...)
. If that fails, still localize on vision. If the VINS is not initialized, follow the „original” if-structure. - On l.822-823 should be the Localization Mode code. This is not yet implemented.
- On l.833-850, a decision is made based on
TRACK_WITH_IMU
. Originally, this only usedTrackLocalMap()
. In the case thatTRACK_WITH_IMU
is not defined, this is still the case. Otherwise, if the VINS is initialized, and no relocalization occurred for 20+ Frames, useTrackLocalMap()
(vision-only; why?!). If relocalization happened more recently,TrackLocalMapWithIMU(...)
. - On l.860-894, if any of the above tracking was successful, not only
mState=OK
, but also when the tracking has been stable for 20+ frames, add this frame to the collection of framesmv20FramesReloc
to recompute the IMU bias. If we are exactly 20 frames since relocalizing, recompute the biases and clearmv20FramesReloc
. - On l.896-902, if the above tracking was not successful, not only set
mState=LOST
, but also clearmv20FramesReloc
. - l.945-949 doesn’t only check if
NeedNewKeyFrame()
, but also ifmbCreateNewKFAfterReloc
. If so,CreateNewKeyFrame()
. It also resetsmbCreateNewKFAfterReloc = false
.
- On the top of the file, a macro
Tracking::MonocularInitialization()
also clears the stored IMU datamvIMUSinceLastKF
when starting initialization on l.1067.Tracking::CreateInitialMapMonocular()
, on l.1143-1157, splits the IMU data frames since the previous KeyFramemvIMUSinceLastKF
in two;IMUData
from before and after themInitialFrame
. It then initializes two KeyFrames (as the original code does) and computes the IMU preintegration. It also clearsmvIMUSinceLastKF
.Tracking::NeedNewKeyFrame()
lists several conditions when a new KeyFrame needs to be generated:- On l.1497-1503, a check is done to see if
LocalMapper::TryInitVIO
is not working in a specific section (whereLocalMapper::mbUpdatingInitPoses == true
). If so, no new KeyFrame is needed. - On l.1514-1517, it is checked if the IMU biases are computed in this Frame. If so, no KeyFrame is needed.
- On l.1552, some threshold factor
thRefRatio
is set to0.8
, instead of0.9
. - On l.1554-1562, two condition variables are set for the test on l.570. Firstly one based on time: if it has been
timegap
time since inserting a KeyFrame, and theLocalMapper
is idle, and there are more than 15 unmatched ORB features, then it’s true. The value oftimegap
depends on if the VINS is initialized. If it is,timegap
is0.5
seconds; otherwise it is0.1
. Conditionc1a
used to look to the number of frames since the last KeyFrame; this new version looks at the time between them.c1a
is nowtrue
iff at least3.0
s has passed. - l.1570 tests these conditions as follows:
((c1a||c1b||c1c)&&c2) || cTimeGap
.cTimeGap
was not included before.
- On l.1497-1503, a check is done to see if
Tracking::CreateNewKeyFrame()
sets theNavStat
and IMU bias of the new KeyFrame, computes the IMU preintegration, and clearsTracking::mvIMUSinceLastKF
.Tracking::UpdateLocalKeyFrames()
adds the previous and next frame for each inspected KeyFrame to themvpLocalKeyFrames
, and sets theirmnTrackReferenceForFrame
to the currently inspected KeyFrame on l.1875-1895`.- If
Tracking::Relocalization()
has not found abMatch
,mbRelocBiasPrepare = true
on l.2064. Tracking::Reset()
does not check if the pointer tompViewer
is set before requesting it to stop. This should definitely be changed.
- It adds the following members:
Viewer
is missing some logic concerningmbStopped
: the original code sets it totrue
, whileLearnVIORB
sets it tofalse
. Also, the linembStopped = false;
after l.56 is missing. Both have the same cause probably:ORB_SLAM2
has been updated afterLearnVIORB
forked it.
Merging
The two repositories are merged; I have created pull requests for both branches ( master and RT ). I didn’t have time for a full test yet.