Compare commits

...

10 Commits

Author SHA1 Message Date
邱棚 a9f462bcbd feat:调整CMake 2024-07-04 11:12:39 +08:00
laobai 6c3b52564b fix: save map break 2023-02-27 19:53:37 +08:00
lao bailaobai 33f7ef16ed update bug from Jason Gao 2023-02-17 23:59:55 +08:00
小白逆袭 18d1ebd345
update 2023-02-13 18:32:10 +08:00
electech6 452befdc4c update readme 2023-02-10 18:31:38 +08:00
lyc a11ca1ed8e 更新rgbd模式下畸变不生效bug 2022-09-15 20:17:45 +08:00
lyc 29f9639cce 更新优化注释 2022-07-21 22:27:32 +08:00
lyc cd59687f0c 更新1 2022-07-21 21:32:11 +08:00
lyc 7efec05be4 修改尺度bug 2022-07-20 20:37:58 +08:00
wuqing 5d57b1d807 修改回环bug 2022-05-28 15:05:22 +08:00
16 changed files with 5602 additions and 4456 deletions

View File

@ -14,12 +14,12 @@ set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -march=native")
# Check C++11 or C++0x support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
message(STATUS "Using flag -std=c++14.")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
add_definitions(-DCOMPILEDWITHC0X)
@ -32,9 +32,9 @@ LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
# opencvdbowros
# 3 4
find_package(OpenCV 3.2)
find_package(OpenCV 4.2)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 3.2 not found.")
message(FATAL_ERROR "OpenCV > 4.2 not found.")
endif()
MESSAGE("OPENCV VERSION:")

View File

@ -14,12 +14,12 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
# Check C++11 or C++0x support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
if(COMPILER_SUPPORTS_CXX14)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
message(STATUS "Using flag -std=c++14.")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
add_definitions(-DCOMPILEDWITHC0X)
@ -32,9 +32,9 @@ LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
# opencvdbowros
# 3 4
find_package(OpenCV 3.2)
find_package(OpenCV 4.2)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 3.2 not found.")
message(FATAL_ERROR "OpenCV > 4.2 not found.")
endif()
find_package(Eigen3 3.1.0 REQUIRED)

View File

@ -57,7 +57,7 @@ Viewer.PointSize: 2.0
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -100
Viewer.ViewpointY: -100.0
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000.0

View File

@ -1,12 +1,10 @@
# ORB-SLAM3 超详细注释
-by 计算机视觉life 公众号旗下开源学习小组SLAM研习社
![DEMO](https://github.com/electech6/ORB_SLAM3_detailed_comments/blob/master/demo.gif)
![课程大纲](https://github.com/electech6/ORB_SLAM3_detailed_comments/blob/master/outline.png)
独家视频课程《VIO灭霸ORB-SLAM3公式推导+源码逐行解析+算法改进》! [点击进入官网](https://cvlife.net/)
[ORB-SLAM3 逐行源码讲解](https://cvlife.net/detail/term_6255372036a53_o5VfgR/25)
点击进入 [小六的机器人SLAM学习圈](https://mp.weixin.qq.com/s?__biz=MzIxOTczOTM4NA==&mid=2247567299&idx=1&sn=2d6b673b6d5e396bd87ec2a28cd3d27d&chksm=97d52254a0a2ab42ff833b5fa733f2213a1ad1ec8ebdb199d96c237aa4cb21fe8e05cc77db8a#rd)4500+人都在这里交流!
----
# ORB-SLAM3

View File

@ -30,12 +30,9 @@ set(SRCS_DUTILS
# opencvdbowros
# 3 4
find_package(OpenCV 3.2 QUIET)
find_package(OpenCV 4.2 QUIET)
if(NOT OpenCV_FOUND)
find_package(OpenCV 3.0 QUIET)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 3.0 not found.")
endif()
message(FATAL_ERROR "OpenCV > 3.0 not found.")
endif()
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)

View File

@ -180,7 +180,7 @@ protected:
std::vector<KeyFrame*> mvpCurrentConnectedKFs;
std::vector<MapPoint*> mvpCurrentMatchedPoints;
std::vector<MapPoint*> mvpLoopMapPoints;
cv::Mat mScw;
g2o::Sim3 mg2oScw;
//-------

View File

@ -123,12 +123,12 @@ public:
int Observations();
void AddObservation(KeyFrame* pKF,int idx);
void EraseObservation(KeyFrame* pKF);
void EraseObservation(KeyFrame* pKF, bool erase = true);
std::tuple<int,int> GetIndexInKeyFrame(KeyFrame* pKF);
bool IsInKeyFrame(KeyFrame* pKF);
void SetBadFlag();
void SetBadFlag(bool erase = true);
bool isBad();
void Replace(MapPoint* pMP);

Binary file not shown.

Before

Width:  |  Height:  |  Size: 103 KiB

View File

@ -323,9 +323,11 @@ bool KannalaBrandt8::epipolarConstrain(GeometricCamera *pCamera2, const cv::KeyP
const Eigen::Matrix3f &R12, const Eigen::Vector3f &t12, const float sigmaLevel, const float unc)
{
Eigen::Vector3f p3D;
// 用三角化出点并验证的这个过程代替极线验证
return this->TriangulateMatches(pCamera2, kp1, kp2, R12, t12, sigmaLevel, unc, p3D) > 0.0001f;
}
// 没用
bool KannalaBrandt8::matchAndtriangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, GeometricCamera *pOther,
Sophus::SE3f &Tcw1, Sophus::SE3f &Tcw2,
const float sigmaLevel1, const float sigmaLevel2,
@ -439,7 +441,7 @@ float KannalaBrandt8::TriangulateMatches(
const Eigen::Matrix3f &R12, const Eigen::Vector3f &t12, const float sigmaLevel,
const float unc, Eigen::Vector3f &p3D)
{
// 1. 得到对应特征点的平面坐标
// 1. 得到对应特征点的归一化平面坐标
Eigen::Vector3f r1 = this->unprojectEig(kp1.pt);
Eigen::Vector3f r2 = pCamera2->unprojectEig(kp2.pt);

View File

@ -831,8 +831,8 @@ void EdgeInertialGS::linearizeOplus()
// Jacobians wrt scale factor
// _jacobianOplus[3] 9*1矩阵 总体来说就是三个残差分别对尺度求导
_jacobianOplus[7].setZero();
_jacobianOplus[7].block<3,1>(3,0) = Rbw1*(VV2->estimate()-VV1->estimate());
_jacobianOplus[7].block<3,1>(6,0) = Rbw1*(VP2->estimate().twb-VP1->estimate().twb-VV1->estimate()*dt);
_jacobianOplus[7].block<3,1>(3,0) = Rbw1*(VV2->estimate()-VV1->estimate()) * s;
_jacobianOplus[7].block<3,1>(6,0) = Rbw1*(VP2->estimate().twb-VP1->estimate().twb-VV1->estimate()*dt) * s;
}
/**

View File

@ -1609,7 +1609,7 @@ void LocalMapping::InitializeIMU(float priorG, float priorA, bool bFIBA)
dirG = dirG/dirG.norm();
// 原本的重力方向
Eigen::Vector3f gI(0.0f, 0.0f, -1.0f);
// 求重力在世界坐标系下的方向与重力在重力坐标系下的方向的叉乘
// 求“重力在重力坐标系下的方向”与的“重力在世界坐标系(纯视觉)下的方向”叉乘
Eigen::Vector3f v = gI.cross(dirG);
// 求叉乘模长
const float nv = v.norm();

View File

@ -179,8 +179,8 @@ void LoopClosing::Run()
// If inertial, force only yaw
// 如果是imu模式并且完成了初始化,强制将焊接变换的 roll 和 pitch 设为0
// 通过物理约束来保证两个坐标轴都是水平的
if ((mpTracker->mSensor==System::IMU_MONOCULAR ||mpTracker->mSensor==System::IMU_STEREO) &&
mpCurrentKF->GetMap()->GetIniertialBA1()) // TODO, maybe with GetIniertialBA1
if ((mpTracker->mSensor==System::IMU_MONOCULAR || mpTracker->mSensor==System::IMU_STEREO || mpTracker->mSensor==System::IMU_RGBD) &&
mpCurrentKF->GetMap()->GetIniertialBA1())
{
Eigen::Vector3d phi = LogSO3(mSold_new.rotation().toRotationMatrix());
phi(0)=0;
@ -693,8 +693,7 @@ bool LoopClosing::DetectAndReffineSim3FromLastKF(KeyFrame* pCurrentKF, KeyFrame*
if(numOptMatches > nProjOptMatches)
{
//!bug, 以下gScw_estimation应该通过上述sim3优化后的位姿来更新。以下mScw应该改为 gscm * gswm^-1
g2o::Sim3 gScw_estimation(Converter::toMatrix3d(mScw.rowRange(0, 3).colRange(0, 3)),
Converter::toVector3d(mScw.rowRange(0, 3).col(3)),1.0);
g2o::Sim3 gScw_estimation(gScw.rotation(), gScw.translation(),1.0);
vector<MapPoint*> vpMatchedMP;
vpMatchedMP.resize(mpCurrentKF->GetMapPointMatches().size(), static_cast<MapPoint*>(NULL));
@ -1218,11 +1217,16 @@ int LoopClosing::FindMatchesByProjection(
{
spCheckKFs.insert(vpKFs[j]);
++nInserted;
// 改成这样
vpCovKFm.push_back(vpKFs[j]);
}
++j;
}
// 这里是原来的代码,这么写不太合适,会出现重复
// 所以下面的插入可以改成放在if里面
// 把每个帧的共视关键帧都加到窗口内
vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end());
// vpCovKFm.insert(vpCovKFm.end(), vpKFs.begin(), vpKFs.end()); // 已放上面
}
}
@ -2275,8 +2279,8 @@ void LoopClosing::MergeLocal()
// Essential graph 优化后可以重新开始局部建图了
mpLocalMapper->Release();
// 全局的BA(永远不会执行)
// 这里没有imu, 所以isImuInitialized一定是false, 此时地图融合Atlas至少2个地图所以第二个条件也一定是false
// 全局的BA后面一串的判断都为true
// !pCurrentMap->isImuInitialized()一定是true
// Step 9 全局BA
if(bRelaunchBA && (!pCurrentMap->isImuInitialized() || (pCurrentMap->KeyFramesInMap()<200 && mpAtlas->CountMaps()==1)))
{

View File

@ -311,6 +311,8 @@ void Map::ApplyScaledRotation(const Sophus::SE3f &T, const float s, const bool b
{
// 更新每一个mp在世界坐标系下的坐标
MapPoint *pMP = *sit;
if (!pMP || pMP->isBad())
continue;
pMP->SetWorldPos(s * Ryw * pMP->GetWorldPos() + tyw);
pMP->UpdateNormalAndDepth();
}
@ -412,9 +414,9 @@ void Map::PreSave(std::set<GeometricCamera *> &spCams)
map<KeyFrame *, std::tuple<int, int>> mpObs = pMPi->GetObservations();
for (map<KeyFrame *, std::tuple<int, int>>::iterator it = mpObs.begin(), end = mpObs.end(); it != end; ++it)
{
if (it->first->GetMap() != this || it->first->isBad())
if (!it->first || it->first->GetMap() != this || it->first->isBad())
{
pMPi->EraseObservation(it->first);
pMPi->EraseObservation(it->first, false);
}
}
}

View File

@ -201,7 +201,7 @@ void MapPoint::AddObservation(KeyFrame* pKF, int idx)
}
// 删除某个关键帧对当前地图点的观测
void MapPoint::EraseObservation(KeyFrame* pKF)
void MapPoint::EraseObservation(KeyFrame* pKF, bool erase)
{
bool bBad=false;
{
@ -236,7 +236,7 @@ void MapPoint::EraseObservation(KeyFrame* pKF)
}
// 告知可以观测到该MapPoint的Frame该MapPoint已被删除
if(bBad)
SetBadFlag();
SetBadFlag(erase);
}
// 能够观测到当前地图点的所有关键帧及该地图点在KF中的索引
@ -260,7 +260,7 @@ int MapPoint::Observations()
* @brief MapPointFrameMapPoint
*
*/
void MapPoint::SetBadFlag()
void MapPoint::SetBadFlag(bool erase)
{
map<KeyFrame*, tuple<int,int>> obs;
{
@ -285,7 +285,8 @@ void MapPoint::SetBadFlag()
}
// 擦除该MapPoint申请的内存
mpMap->EraseMapPoint(this);
if (erase)
mpMap->EraseMapPoint(this);
}
/**
@ -769,7 +770,9 @@ void MapPoint::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP)
mBackupObservationsId1.clear();
mBackupObservationsId2.clear();
// Save the id and position in each KF who view it
for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(), end = mObservations.end(); it != end; ++it)
std::vector<KeyFrame*> erase_kfs;
for(std::map<KeyFrame*,std::tuple<int,int> >::const_iterator it = mObservations.begin(),
end = mObservations.end(); it != end; ++it)
{
KeyFrame* pKFi = it->first;
if(spKF.find(pKFi) != spKF.end())
@ -779,10 +782,11 @@ void MapPoint::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP)
}
else
{
EraseObservation(pKFi);
erase_kfs.push_back(pKFi);
}
}
for (auto pKFi : erase_kfs)
EraseObservation(pKFi, false);
// Save the id of the reference KF
// 3. 备份参考关键帧ID
if(spKF.find(mpRefKF) != spKF.end())

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff