前言
OpenVINS自带评估工具,这里记录一下使用方法,我是以VIRAL数据集为例,但是目前仍然有问题,发现误差很大,我还没搞明白哪里出了问题。
工具介绍
主要参考
https://docs.openvins.com/eval-error.html
https://blog.csdn.net/crp997576280/article/details/121204219
数据记录
通过ov_eval中的record.launch来完成,需要根据需要进行修改,我的如下,VIRAL数据集eee_01序列,分别记录了真值和估计轨迹值。(VIRAL的真值在bag包里有因此可以订阅话题,但是VIRAL数据集有个问题是真值只有位置没有姿态,有点坑)
<launch>
<!-- what ros bag to play -->
<arg name="bag_name" default="eee_01" />
<arg name="bag_path" default="/home/merlincs/workspace/dataset/VIRAL/" />
<!-- where to save the recorded poses -->
<arg name="path_save" default="/home/merlincs/workspace/catkin_uwbvio/src/open_vins/ov_data/viral/" />
<!-- record the trajectory -->
<node name="recorder_gt" pkg="ov_eval" type="pose_to_file" output="screen" required="true">
<param name="topic" type="str" value="/leica/pose/relative" />
<param name="topic_type" type="str" value="PoseStamped" />
<param name="output" type="str" value="$(arg path_save)/$(arg bag_name)/eee_01_gt.txt" />
</node>
<node name="recorder_estimate" pkg="ov_eval" type="pose_to_file" output="screen" required="true">
<param name="topic" type="str" value="/ov_msckf/poseimu" />
<param name="topic_type" type="str" value="PoseWithCovarianceStamped" />
<param name="output" type="str" value="$(arg path_save)/$(arg bag_name)/eee_01_estim.txt" />
</node>
<!-- play the dataset -->
<node pkg="rosbag" type="play" name="rosbag" args="-r 4 $(arg bag_path)/$(arg bag_name)/eee_01.bag" required="true"/>
</launch>
根据自己的需要修改上面文件后,开始跑一下eee_01序列数据集,流程如下:
#终端1
roscore
#终端2
source devel/setup.bash
roslaunch ov_msckf subscribe.launch config:=viral
#终端3
source devel/setup.bash
roslaunch ov_eval record.launch
之后在record.launch中配置的保存路径下面就能看到记录好数据的文件了:
结果评估
记录好数据后就拿到了真值文件和估计轨迹文件,数据组织格式也是根据上面record中的配置完成的,PoseWithCovarianceStamped如下:
#timestamp(s) tx ty tz qx qy qz qw Pr11 Pr12 Pr13 Pr22 Pr23 Pr33 Pt11 Pt12 Pt13 Pt22 Pt23 Pt33
接下俩就可以进行单个序列的轨迹评估了,方法如下:
#打开终端
source devel/setup.bash
rosrun ov_eval error_singlerun posyaw /home/merlincs/workspace/catkin_uwbvio/src/open_vins/ov_data/viral/eee_01/eee_01_estim.txt /home/merlincs/workspace/catkin_uwbvio/src/open_vins/ov_data/viral/eee_01/eee_01_gt.txt
#打开终端
source devel/setup.bash
rosrun ov_eval plot_trajectories posyaw /home/merlincs/workspace/catkin_uwbvio/src/open_vins/ov_data/viral/eee_01/eee_01_estim.txt /home/merlincs/workspace/catkin_uwbvio/src/open_vins/ov_data/viral/eee_01/eee_01_gt.txt
结果如下,误差好大啊,感觉不太正常。
接下来要确认一下结果是不是正常,不正常是哪一步出现了问题,评估过程应该没错,还是数据集配置那有问题吗。
掌握了评估定位结果的方法,接下来就可以进行改造看看效果了。
更新:
对齐方式有了问题,因为VIRAL数据集只有位置真值,因此对齐旋转不准确。修改posyaw为sim3效果会好一些,具体原理还需要学习。