将ORB SLAM3修改成了Mac上能运行的版本,但是存在加载词库特别慢的问题。通常需要二十多分钟才加载完毕。一直卡在Loading ORB Vocabulary. This could take a while..阶段。
逐步排查发现主要是在循环中不停的申请用于存储描述子的动态内存这步比较耗时。
//System.cc中的
bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);//加载词库
//TemplatedVocabulary.h中的
F::fromString(m_nodes[nid].descriptor, ssd.str());//循环中调用这个
//FORB.cpp
a.create(1, FORB::L, CV_8U);//fromString一直在申请内存,该句比较耗时
循环中申请比较耗时,改为开头统一申请,修改FORB.cpp文件中的内容fromString函数如下:
//统一申请
//FORB::TDescriptor其实就是cv::Mat结构
int nMaxNumDes = 1082174;//1082074
int nIndx = 0;
vector<FORB::TDescriptor> vDes(nMaxNumDes,cv::Mat(1, FORB::L, CV_8U));
void FORB::fromString(FORB::TDescriptor &a, const std::string &s)
{
//a.create(1, FORB::L, CV_8U);//原先的逐个申请较慢,换成使用统一申请的内存
a=vDes[nIndx++];
unsigned char *p = a.ptr<unsigned char>();
stringstream ss(s);
for(int i = 0; i < FORB::L; ++i, ++p)
{
int n;
ss >> n;
if(!ss.fail())
*p = (unsigned char)n;
}
}
修改完成后重新编译一下DBoW2即可。
博客内容讲述了作者将ORBSLAM3适配为Mac版本后遇到的词库加载速度慢问题,经过排查发现循环中动态内存申请是主要耗时点。作者通过在循环外预先分配内存,显著减少了加载时间。修改后的FORB.cpp文件中,使用一次性内存分配来替代循环内的内存申请,从而提高了加载效率。
752

被折叠的 条评论
为什么被折叠?



