一.问题说明
在小车上部署好VINS-Fusion后,进行实物测试。使用命令
rosrun loop-fusion loop-fusion-node config.yaml
时发生报错:
config_file: euroc_stereo_imu_config2.yaml
vocabulary_file/home/amov/catkin_vinfusion/src/VINS-Fusion-master/loop_fusion/../support_files/brief_k10L6.bin
段错误 (核心已转储)
二.判断问题
找到代码块中报错的位置是VINS_Fusion/loop_fusion/src/pose_graph.cpp 的 64行
void PoseGraph::loadVocabulary(std::string voc_path)
{
voc = new BriefVocabulary(voc_path);
db.setVocabulary(*voc, false, 0);
}
中的BriefVocabulary 构造函数报错。再三查看,确认路径设置是没有问题的。
使用代码跳转功能进入到该构造函数中去,地址为:loop_fusion/src/ThirdParty/DBoW/TemplatedVocabulary.h
使用输出调试,定位到代码出错位置,是loadBin方法中对于读取文件中的循环代码块中:
m_nodes.resize(voc.nNodes + 1); // +1 to include root
cout<<"m_nodes size is:"<<m_nodes.size()<<endl;
m_nodes[0].id = 0;
for(unsigned int i = 0; i < voc.nNodes; ++i)
{
NodeId nid = voc.nodes[i].nodeId;
NodeId pid = voc.nodes[i].parentId;
WordValue weight = voc.nodes[i].weight;
// std::cerr << "Invalid node ID: nid=" << nid << ", pid=" << pid << ", at index i=" << i << std::endl;
// if (nid >= m_nodes.size() || pid >= m_nodes.size()) {
// std::cerr << "Invalid node ID: nid=" << nid << ", pid=" << pid << ", at index i=" << i << std::endl;
// continue;
// }
m_nodes[nid].id = nid;
m_nodes[nid].parent = pid;
m_nodes[nid].weight = weight;
m_nodes[pid].children.push_back(nid);
if (nid >= m_nodes.size() || pid >= m_nodes.size()) {
std::cerr << "Invalid node ID: nid=" << nid << ", pid=" << pid << ", at index i=" << i << std::endl;
continue;
}
if (voc.nodes[i].descriptor == nullptr) {
std::cerr << "Invalid descriptor pointer at index i=" << i << std::endl;
continue;
}
// Sorry to break template here
m_nodes[nid].descriptor = boost::dynamic_bitset<>(voc.nodes[i].descriptor, voc.nodes[i].descriptor + 4);
if (i < 5) {
std::string test;
boost::to_string(m_nodes[nid].descriptor, test);
//cout << "descriptor[" << i << "] = " << test << endl;
}
}
使用代码:
if (nid >= m_nodes.size() || pid >= m_nodes.size()) {
std::cerr << "Invalid node ID: nid=" << nid << ", pid=" << pid << ", at index i=" << i << std::endl;
continue;
}
发现大量不合理数据,其中nid 和 pid的值远远大于m_nodes设定的范围。

判断是文件出问题了,于是从u盘中重新复制一份brief_k10L6.bin 可是问题依旧没有解决。刚好我的台式机上也部署了VINS-Fusion, 其中loop-fuison 是可以运行的,找到相应的这个循环的代码块进行输出:

这里输出正常,而且通过了循环代码块,表明源文件是正常的。我突然想到一种可能,不会不是因为把该文件放入到u盘上的时候这个文件的内容发生了改变导致的?所以打算使用scp命令复制该文件。
三. 解决办法
将硬件平台和电脑主机连接上同一网段,使用scp命令进行文件的传输:
scp -r brief_k10L6.bin username@remote_host:/path/to/remote/destination
将文件重传一遍。继续运行loop_fuison,发现这个错误消除。

对于上图中,下面的配置文件位置出错的问题,参考博客:
https://blog.youkuaiyun.com/qq_52710816/article/details/125046226
将loop-fusion中的pose_graph_node.cpp 大约448行的 cam0Path进行修改:
std::string cam0Calib;
fsSettings["cam0_calib"] >> cam0Calib;
// 修改这里
// std::string cam0Path = configPath + "/" + cam0Calib;
std::string cam0Path = cam0Calib;
重新编译,在配置文件目录下运行loop_fusion即可。
1324

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



