调通ORBSLAM2 单目SLAM与 RGBD-SLAM过程说明【Debug模式vector越界问题待解决】
在我编译 ORBSLAM FOR WINDOWS过程,CMAKE生成sln,你直接打开sln,查看mono_tum 与 rgbd_tum工程属性包含,我得出了 有关应用 orbslam2
的属性表;如下:
//【DebugX64模式】==============================================================================================================================
包含目录
E:\ORBSLAM24Windows-master\include
E:\ORBSLAM24Windows-master
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\include
库目录
E:\ORBSLAM24Windows-master\lib\Debug
E:\ORBSLAM24Windows-master\Thirdparty\DBoW2\lib\Debug
E:\ORBSLAM24Windows-master\Thirdparty\g2o\lib\Debug
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\lib\Debug
链接器-输入
---------------------------------
E:\ORBSLAM24Windows-master\lib\Debug\ORB_SLAM2.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\lib\Debug\pangolin.lib
opengl32.lib
glu32.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\glew\lib\glewd.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\libpng\lib\libpng16_staticd.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\zlib\lib\zlibstaticd.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\libjpeg\lib\jpeg.lib
DBoW2.lib
g2o.lib
pangolin.lib
kernel32.lib
user32.lib
gdi32.lib
winspool.lib
shell32.lib
ole32.lib
oleaut32.lib
uuid.lib
comdlg32.lib
advapi32.lib
如果出现问题:LINK : warning LNK4098: 默认库“MSVCRT”与其他库的使用冲突;请使用 /NODEFAULT
解决:【项目(不是属性表)】->【属性】->【配置属性】->【连接器】->【命令行】,输入:/NODEFAULTLIB:msvcrt.lib
//【ReleaseX64模式】==============================================================================================================================
包含目录
E:\ORBSLAM24Windows-master\include
E:\ORBSLAM24Windows-master
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\include
库目录
E:\ORBSLAM24Windows-master\lib\Release
E:\ORBSLAM24Windows-master\Thirdparty\DBoW2\lib\Release
E:\ORBSLAM24Windows-master\Thirdparty\g2o\lib\Release
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\lib\Release
链接器-输入
---------------------------------
E:\ORBSLAM24Windows-master\lib\Release\ORB_SLAM2.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\lib\Release\pangolin.lib
opengl32.lib
glu32.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\glew\lib\glew.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\libpng\lib\libpng16_static.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\zlib\lib\zlibstatic.lib
E:\ORBSLAM24Windows-master\Thirdparty\Pangolin\build\external\libjpeg\lib\jpeg.lib
DBoW2.lib
g2o.lib
pangolin.lib
kernel32.lib
user32.lib
gdi32.lib
winspool.lib
shell32.lib
ole32.lib
oleaut32.lib
uuid.lib
comdlg32.lib
advapi32.lib
如果出现问题:LINK : warning LNK4098: 默认库“MSVCRT”与其他库的使用冲突;请使用 /NODEFAULT
解决:【项目(不是属性表)】->【属性】->【配置属性】->【连接器】->【命令行】,输入:/NODEFAULTLIB:msvcrt.lib
//【单目SLAM】 #include<iostream> #include<algorithm> #include<fstream> #include<chrono> #include<opencv2/core/core.hpp> #include<System.h> using namespace std; void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &vTimestamps); int main(int argc, char **argv) { if(argc != 4) { cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence" << endl; return 1; } // Retrieve paths to images vector<string> vstrImageFilenames; vector<double> vTimestamps; string strFile = string(argv[3])+"/rgb.txt"; LoadImages(strFile, vstrImageFilenames, vTimestamps); int nImages = vstrImageFilenames.size(); string str_ = string(argv[3]) + "/" + vstrImageFilenames[0]; cout << "test!!!!!!!!!!!!!!!!!!!1" << str_ << endl; cv::Mat testImage = cv::imread(str_, -1); imshow("test", testImage); cv::waitKey(0); // Create SLAM system. It initializes all system threads and gets ready to process frames. ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true); // Vector for tracking time statistics vector<float> vTimesTrack; vTimesTrack.resize(nImages); cout << endl << "-------" << endl; cout << "Start processing sequence ..." << endl; cout << "Images in the sequence: " << nImages << endl << endl; // Main loop cv::Mat im; for(int ni=0; ni<nImages; ni++) { // Read image from file im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED); double tframe = vTimestamps[ni]; if(im.empty()) { cerr << endl << "Failed to load image at: " << string(argv[3]) << "/" << vstrImageFilenames[ni] << endl; return 1; } //#ifdef COMPILEDWITHC11【注:在下面RGBD SLAM代码中 c++ 11 新特性检测代码时间 我也这样注释了,其实你可以按照编译源代码,sln项目中设置支持c++11】 std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); //#else // std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); //#endif // Pass the image to the SLAM system SLAM.TrackMonocular(im,tframe); //#ifdef COMPILEDWITHC11 std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); //#else // std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); //#endif double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); vTimesTrack[ni]=ttrack; // Wait to load the next frame double T=0; if(ni<nImages-1) T = vTimestamps[ni+1]-tframe; else if(ni>0) T = tframe-vTimestamps[ni-1]; if(ttrack<T) usleep((T-ttrack)*1e6); } // Stop all threads SLAM.Shutdown(); // Tracking time statistics sort(vTimesTrack.begin(),vTimesTrack.end()); float totaltime = 0; for(int ni=0; ni<nImages; ni++) { totaltime+=vTimesTrack[ni]; } cout << "-------" << endl << endl; cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; cout << "mean tracking time: " << totaltime/nImages << endl; // Save camera trajectory SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); return 0; } void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &vTimestamps) { ifstream f; f.open(strFile.c_str()); // skip first three lines string s0; getline(f,s0); getline(f,s0); getline(f,s0); while(!f.eof()) { string s; getline(f,s); if(!s.empty()) { stringstream ss; ss << s; double t; string sRGB; ss >> t; vTimestamps.push_back(t); ss >> sRGB; vstrImageFilenames.push_back(sRGB); } } }
//【RGBD-SLAM】 #include<iostream> #include<algorithm> #include<fstream> #include<chrono> #include<opencv2/core/core.hpp> #include<System.h> using namespace std; void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB, vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps); int main(int argc, char **argv) { if(argc != 5) { cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association" << endl; return 1; } // Retrieve paths to images vector<string> vstrImageFilenamesRGB;//彩图路径 vector<string> vstrImageFilenamesD;//深度图路径 vector<double> vTimestamps;//时间戳 string strAssociationFilename = string(argv[4]);//关联文件 LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps);//加载图 // 检查深度图与彩色图数量是否一致 int nImages = vstrImageFilenamesRGB.size(); if(vstrImageFilenamesRGB.empty()) { cerr << endl << "No images found in provided path." << endl; return 1; } else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size()) { cerr << endl << "Different number of images for rgb and depth." << endl; return 1; } //*******************【测试】 //string str_ = string(argv[3]) + "/" + vstrImageFilenamesRGB[0]; // + "/" 写到命令行参数中去 string str_ = string(argv[3]) + vstrImageFilenamesRGB[0]; cout << "test!!!!!!!!!!!!!!!!!!!1" << str_ << endl; cv::Mat testImage = cv::imread(str_, -1); imshow("test", testImage); cv::waitKey(0); //*******************【测试】 // 创建 SLAM system.它初始化系统所有线程,同时准备处理帧 //【注:这里加载字典太鸡巴满了,建议改成bin格式】 ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD,true); // Vector for tracking time statistics vector<float> vTimesTrack; vTimesTrack.resize(nImages);//预留空间 cout << endl << "-------" << endl; cout << "Start processing sequence ..." << endl; cout << "Images in the sequence: " << nImages << endl << endl; //*********************************************************************************************************************** // 主循环 cv::Mat imRGB, imD; for(int ni=0; ni<nImages; ni++) { // 读取深度图和彩色图 //imRGB = cv::imread(string(argv[3])+"/"+vstrImageFilenamesRGB[ni],CV_LOAD_IMAGE_UNCHANGED); //imD = cv::imread(string(argv[3])+"/"+vstrImageFilenamesD[ni],CV_LOAD_IMAGE_UNCHANGED); imRGB = cv::imread(string(argv[3]) + vstrImageFilenamesRGB[ni], CV_LOAD_IMAGE_UNCHANGED); imD = cv::imread(string(argv[3]) + vstrImageFilenamesD[ni], CV_LOAD_IMAGE_UNCHANGED); double tframe = vTimestamps[ni]; if(imRGB.empty()) { cerr << endl << "Failed to load image at: " << string(argv[3]) << "/" << vstrImageFilenamesRGB[ni] << endl; return 1; } std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();//计算时间 SLAM.TrackRGBD(imRGB,imD,tframe); std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();//计算时间 double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();//计算时间 vTimesTrack[ni]=ttrack; // 等待加载下一帧 double T=0; if(ni<nImages-1) T = vTimestamps[ni+1]-tframe; else if(ni>0) T = tframe-vTimestamps[ni-1]; if(ttrack<T) usleep((T-ttrack)*1e6); } //*********************************************************************************************************************** // Stop all threads SLAM.Shutdown(); // Tracking time statistics sort(vTimesTrack.begin(),vTimesTrack.end()); float totaltime = 0; for(int ni=0; ni<nImages; ni++) { totaltime+=vTimesTrack[ni]; } cout << "-------" << endl << endl; cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; cout << "mean tracking time: " << totaltime/nImages << endl; // Save camera trajectory SLAM.SaveTrajectoryTUM("CameraTrajectory.txt"); SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); system("pause"); return 0; } void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB, vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps) { ifstream fAssociation; fAssociation.open(strAssociationFilename.c_str()); while(!fAssociation.eof()) { string s; getline(fAssociation,s); if(!s.empty()) { stringstream ss; ss << s; double t; string sRGB, sD; ss >> t; vTimestamps.push_back(t); ss >> sRGB; vstrImageFilenamesRGB.push_back(sRGB); ss >> t; ss >> sD; vstrImageFilenamesD.push_back(sD); } } }