赞
踩
在运行LeGO-LOAM的时候环境已经按照readme和网上的教程配置完成了。但在play rosbag的时候发现bagtime使用的是系统时间,但是我的sim_time 是使用的true的。所以导致了一个问题就是在playbag包的时候会和其他tf的时间戳对不上。如下图所示map_to_carmera_init使用的是bag录制的时间。后续的几个变换使用的是odometry的时间戳,也是sim_time.
时间对不上就报了如下的错误:
For frame [base_link]: No transform to fixed frame [map]. TF error: [Lookup would require extrapolation 1694572574.409007311s into the past. Requested time 32.038040161 but the earliest data is at time 1694572606.447047472, when looking up transform from frame [base_link] to frame [map]]
接下来介绍解决方法:
使用了虚拟时间:
<param name="/use_sim_time" value="true" />
Bag Time为系统时间:这是因为在录制bag包的时候用了ros::Time::now();
所以要把原本输出bagtime使用的系统时间,改为数据集的时间戳,即timestamp。又因为直接使用数据集的时间戳时,开始时间可能会太小会报错:不能插入信息到ros::Time::min(),所以最好在时间戳后面加一个小时间。更改如下:
- // 使用rostime
- // if (to_bag)
- // {
- // bag_out.write("/image_left", ros::Time::now(), image_left_msg);
- // bag_out.write("/image_right", ros::Time::now(), image_right_msg);
- // bag_out.write("/velodyne_points", ros::Time::now(), laser_cloud_msg);
- // bag_out.write("/path_gt", ros::Time::now(), pathGT);
- // bag_out.write("/odometry_gt", ros::Time::now(), odomGT);
- // }
- // 使用ros::Time().fromSec(timestamp)
- if (to_bag)
- { std::cout<<"time is"<<ros::Time().fromSec(timestamp+0.01);
- bag_out.write("/image_left", ros::Time().fromSec(timestamp+0.01), image_left_msg);
- bag_out.write("/image_right", ros::Time().fromSec(timestamp+0.01), image_right_msg);
- bag_out.write("/velodyne_points",ros::Time().fromSec(timestamp+0.01), laser_cloud_msg);
- bag_out.write("/path_gt",ros::Time().fromSec(timestamp+1), pathGT);
- bag_out.write("/odometry_gt",ros::Time().fromSec(timestamp+1), odomGT);
- }
更改代码后重新录制bag包,发现现在的bagtime已经不在是系统时间。
现在的tf_tf_tree也正常了。
现在地图也能正常跑通啦
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。