ORB-slam3问题汇总(更新中)

1,072 阅读1分钟

因项目要求要跑ORB-SLAM3,在安装和测试的过程中遇到了很多问题,特此在这里记录一下: 一.硬件介绍: 硬件:Intel Realsense D455

二.编译: 关于Pangolin: blog.csdn.net/Robert_Q/ar…

三.运行Example 目前只跑了Examples/Stereo,因此在这里主要记录这里面的问题

  1. 修改配置文件
  2. 修改Settings.cc 在Settings.cc中存在一处逻辑错误,会导致在加载camera2参数时报Segmentation fault. 修改前:
// 修改此方法
    ostream &operator<<(std::ostream& output, const Settings& settings){
        output << "SLAM settings: " << endl;
        ...
        ...
        if(settings.sensor_ == System::STEREO || settings.sensor_ == System::IMU_STEREO){
            output << "\t-Camera 2 parameters (";
            if(settings.cameraType_ == Settings::PinHole || settings.cameraType_ ==  Settings::Rectified){
                cout<<"Pinhole"<<endl;
                output << "Pinhole";
            }
            else{
                output << "Kannala-Brandt";
            }
            output << ")" << ": [";
            for(size_t i = 0; i < settings.originalCalib2_->size(); i++){
                cout<<settings.originalCalib2_->getParameter(i)<<endl;
                output << " " << settings.originalCalib2_->getParameter(i);
            }
            output << " ]" << endl;

            if(!settings.vPinHoleDistorsion2_.empty()){
                output << "\t-Camera 2 distortion parameters: [ ";
                for(float d : settings.vPinHoleDistorsion2_){
                    output << " " << d;
                }
                output << " ]" << endl;
            }
        }

修改后:

    ostream &operator<<(std::ostream& output, const Settings& settings){
        output << "SLAM settings: " << endl;
        ...
        ...
        if(settings.cameraType_ == Settings::PinHole)
        {
            output << ")" << ": [";
            for(size_t i = 0; i < settings.originalCalib2_->size(); i++){
                output << " " << settings.originalCalib2_->getParameter(i);
            }
            output << " ]" << endl;
        }
        else if(settings.cameraType_ == Settings::Rectified)
        {
            output << ")" << ": [";
            for(size_t i = 0; i < settings.originalCalib1_->size(); i++){
                output << " " << settings.originalCalib1_->getParameter(i);
            }
            output << " ]" << endl;
        }

参考自:参考此处

  1. 修改System.cc 问题1:在保存地图时,经常会出现Segmentation fault,导致地图无法保存,在debug了好久后,目前找到了可能的原因: 在UI界面点击stop后,stereo_realsense_D435i.cc中的while (!SLAM.isShutDown())会返回mbShutDown这个flag的状态,而这个flag是在System::shutdown()中进行修改的.
void System::Shutdown()
{
    {
        unique_lock<mutex> lock(mMutexReset);
        mbShutDown = true;
    }

    cout << "Shutdown" << endl;

    mpLocalMapper->RequestFinish();
    mpLoopCloser->RequestFinish();
    ...

a. shutdown()是注册在界面端的函数.在界面点击stop()后, mbShutDown 立刻会被设置为 true; b. 同时在./Examples/Stereo/stereo_realsense_D435i.cc中的while (!SLAM.isShutDown())会检查mbShutDown的值.当mbShutDown==true时,退出while循环. 推出while循环后,后面已无可执行的命令,整个程序退出,SLAM对象销毁. c. 但是当地图文件很大时,注册在界面端的函数依旧在执行,最后在SaveAtlas()时,会访问SLAM对象中的一些成员,如mStrVocabularyFilePath变量,但此时SLAM已经被销毁,最后访问变量出错,导致Segmentation fault.

修改

void System::Shutdown()
{
    {
        unique_lock<mutex> lock(mMutexReset);
    }
    cout << "Shutdown" << endl;
    mpLocalMapper->RequestFinish();
    mpLoopCloser->RequestFinish();
    
    ...
    
    if(!mStrSaveAtlasToFile.empty())
    {
        Verbose::PrintMess("Atlas saving to file " + mStrSaveAtlasToFile, Verbose::VERBOSITY_NORMAL);
        SaveAtlas(FileType::BINARY_FILE);
    }
    /*if(mpViewer)
        pangolin::BindToContext("ORB-SLAM2: Map Viewer");*/
#ifdef REGISTER_TIMES
    mpTracker->PrintTimeStats();
#endif
     mbShutDown = true;
}

将mbShutDown = true;放在程序的最后,在执行完地图保存后,再修改flag.