orbslam3_docker 实践 EuRoC 数据集

 


git clone https://github.com/jahaniam/orbslam3_docker.git
cd orbslam3_docker
./download_dataset_sample.sh
├── Datasets
│   └── EuRoC
│   └── MH01
│   └── mav0
│   ├── cam0
│   │   └── data
│   ├── cam1
│   │   └── data
│   ├── imu0
│   ├── leica0
│   └── state_groundtruth_estimate0
./build_container_cuda.sh
docker ps
docker exec -it container_id bash
cd /ORB_SLAM3/Examples
# 单目+IMU
./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml /Datasets/EuRoC/MH01 ./Monocular-Inertial/EuRoC_TimeStamps/MH01.txt dataset-MH01_monoi
# 单目
./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml /Datasets/EuRoC/MH01 ./Monocular/EuRoC_TimeStamps/MH01.txt dataset-MH01_mono

但是没有任何可视化,因此修改了代码:

https://github.com/jahaniam/orbslam3_docker/issues/21#issuecomment-1887284443

false 改为 true

cd /ORB_SLAM3/build
make -j8
cd /ORB_SLAM3/Examples
./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml /Datasets/EuRoC/MH01 ./Monocular/EuRoC_TimeStamps/MH01.txt dataset-MH01_mono

跑自己的数据集

./Monocular/mono_dji ../Vocabulary/ORBvoc.txt ./Monocular/Dji.yaml /Datasets/DJI6-phantom3-village-unified ./Monocular/Dji_TimeStamps/DJI6-phantom3-village-unified.txt dataset-Dji-village_mono

增加保存点云的代码:

ORB_SLAM3/include/System.h:160:

void SavePointCloud(const string &filename);

ORB_SLAM3/src/System.cc:1175:

void System::SavePointCloud(const string &filename){
// Code is based on MapDrawer::DrawMapPoints()
cout << endl << "Saving map point coordinates to " << filename << " ..." << endl;
cout << endl << "Number of maps is: " << mpAtlas->CountMaps() << endl;
// TODO Get all maps or is the current active map is enough?
// vector<Map*> vpAllMaps = mpAtlas->GetAllMaps()
Map* pActiveMap = mpAtlas->GetCurrentMap();
if(!pActiveMap) {
cout << endl << "There is no active map (pActiveMap is null)" << endl;
return;
}
// Vectors containing pointers to MapPoint objects contained in the maps
// Vector of pointers for Map Points -- vpMPs
// Vector of pointers for Reference Map Points -- vpRefMPs
// TODO figure out the difference between Reference Map Points and normal Map Points
const vector<MapPoint*> &vpMPs = pActiveMap->GetAllMapPoints();
const vector<MapPoint*> &vpRefMPs = pActiveMap->GetReferenceMapPoints();
if(vpMPs.empty()){
cout << endl << "Vector of map points vpMPs is empty!" << endl;
return;
}
// Use a set for fast lookup of reference frames
set<MapPoint*> spRefMPs(vpRefMPs.begin(), vpRefMPs.end());
// Get the output file stream in fixed-point format for map points
ofstream f;
f << "pos_x, pos_y, pos_z";
f.open(filename.c_str());
f << fixed;
// TODO figure out if we need to consider whether the presence of IMU
// requires some transforms/exceptions
// Iterate over map points, skip "bad" ones and reference map points
for (size_t i=0, iend=vpMPs.size(); i<iend;i++)
{
if (vpMPs[i]->isBad() || spRefMPs.count(vpMPs[i])){
continue;
}
Eigen::Matrix<float,3,1> pos = vpMPs[i]->GetWorldPos();
f << pos(0) << ", " << pos(1) << ", " << pos(2) << endl;
}
// Close the output stream
f.close();
// Get the output file stream in fixed-point format for reference map points
f.open(("ref_" + filename).c_str());
f << "pos_x, pos_y, pos_z" << endl;
f << fixed;
// Iterate over reference map points, skip if bad
for (set<MapPoint*>::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++)
{
if((*sit)->isBad()){
continue;
}
Eigen::Matrix<float,3,1> pos = (*sit)->GetWorldPos();
f << pos(0) << ", " << pos(1) << ", " << pos(2) << endl;
}
// Close the output stream
f.close();
}
posted @   Zenith_Hugh  阅读(8)  评论(0编辑  收藏  举报
相关博文:
阅读排行:
· 阿里最新开源QwQ-32B,效果媲美deepseek-r1满血版,部署成本又又又降低了!
· 单线程的Redis速度为什么快?
· SQL Server 2025 AI相关能力初探
· AI编程工具终极对决:字节Trae VS Cursor,谁才是开发者新宠?
· 展开说说关于C#中ORM框架的用法!
点击右上角即可分享
微信分享提示

喜欢请打赏

扫描二维码打赏

微信打赏