最近使用一个orb-slam2
修改版跑euroc数据集,在使用evo评估绝对轨迹误差时出现下面的报错:
found no matching timestamps between CameraTrajectory.txt and gt/MH01_GT.txt with max. time diff 0.01 (s) and time offset 0.0 (s)
然后对比了一下生成的轨迹和groundtruth
,发现时间戳的格式不一样,如下:
定位到问题是在例子程序中调用的轨迹保存函数是SaveTrajectoryTUM
,因此得到的时间戳的小数点位是按照TUM
数据集保存的
解决: 找到System.cc
中的SaveTrajectoryTUM
函数,将*lT
改为1e9*(*lT)
f << setprecision(6) << (*lT) << " " << setprecision(9)
<< twc.at<float>(0) << " " << twc.at<float>(1) << " "<< twc.at<float>(2) << " "
<< q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9)
<< twc.at<float>(0) << " " << twc.at<float>(1) << " "<< twc.at<float>(2) << " "
<< q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)