MIT和软件所的数据集

根据我的经验,先启动cartographer后,等待出现下面的日志,然后再播放bag。如果这个日志没出现,播放bag通常不会成功开始建图

1
2
[/cartographer_node   node.cc:886] Expected topic "scan" (trajectory 0) (resolved topic "/base_scan") but no publisher is currently active.
[/cartographer_node node.cc:895] Currently available topics are: /constraint_list,/submap_list,/scan_matched_points2,/rosout,/tf,/rosout_agg,/map,/trajectory_node_list,/landmark_poses_list,

MIT数据集老出问题,德意志博物馆数据集却从不出问题 最好数据集里不要有tf信息
博物馆的tf
MIT数据集的 tf

博物馆的地图大小 3066平方米

MIT的数据集运行

这个数据集使用雷达北洋UTM-30LX,也就是LOAM论文所用的雷达,有一个问题是它的机器人是会坐电梯在楼层之间跑的,因此需要选择一个只在一个平面上跑的数据集2011-03-28-08-38-59.bag

从TF变换树可以看到,这里的里程计信息是采用经过EKF滤波之后的里程计坐标系/robot_pose_ekf/odom_combined,而不是直接的base_odometry/odom第2个问题来了:cartographer需要的里程计消息是nav_msgs/Odometry,但是/robot_pose_ekf/odom_combined的类型是geometry_msgs/PoseWithCovarianceStamped,在播放rosbag时会报错,无法建图。于是想用原来的里程计/base_odometry/odom,结果发现缺少child_frame_id,一般为base_link。无法给bag消息加坐标系,只能写一个程序mit_to_odom做转换

我们要使用数据集的IMU和odom,否则建图不能进行,日志如下

1
2
3
4
[/cartographer_node] [local_trajectory_builder_2d.cc:136] time_first_point: 634369235390529797
[/cartographer_node] [local_trajectory_builder_2d.cc:137] GetLastPoseTime: 634369235390647384
[/cartographer_node] [local_trajectory_builder_2d.cc:138] Extrapolator is still initializing
[/cartographer_node] [pose_graph_2d.cc:148] Inserted submap (0, 0).

阻塞在
1
2
3
4
5
if (time_first_point < extrapolator_->GetLastPoseTime() )
{
LOG(INFO) << "Extrapolator is still initializing.";
return nullptr;
}

launch如下,不能加<param name="/use_sim_time" value="true" />,否则cartographer一直阻塞。

1
2
3
4
5
6
7
8
9
10
11
12
13
<launch>
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename mit_stata_odom.lua"
output="screen">
<remap from="scan" to="base_scan" />
<remap from="imu" to="torso_lift_imu/data" />
</node>

<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>

TF_REPEATED_DATA 问题

1
2
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame odom at time 1301326803.532597 according to authority unknown_publisher
at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.5/src/buffer_core.cpp

这个问题困扰了我好长时间,后来发现是数据集发布了坐标转换odom_combined —— base_footprint,而cartographer也容易发布这个变换,此时仍然可以建图,但这个报警无穷无尽,没法看其他日志了。

如此解决:首先在播放bag的终端,先运行rosparam set use_sim_time true,lua设置如下

1
2
3
4
5
6
7
8
9
map_frame = "map",
tracking_frame = "imu_link",
published_frame = "odom_combined",
odom_frame = "odom_combined",

provide_odom_frame = false,
use_odometry = true,

TRAJECTORY_BUILDER_2D.use_imu_data = true

但是Rviz终端也出现了报警,按说把Rviz里的Submaps的Tracking Frame改为lua 文件中的 tracking_frame 即可,但是我改了后无效,把base_footprintbase_link都试了一遍也没有解决

1
[ WARN] Could not compute submap fading: Could not find a connection between 'map' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees

这样导致无法获得`base_link`在`map`中的坐标

mapbase_link的关系问题

数据集中已经包含了odom_combinedbase_link之间的tf关系,运行carto之后会获得odom_combinedmap之间的关系,但是无法获得mapbase_link之间的tf,运行rosrun tf tf_echo map base_link报警如下

1
Exception thrown:Lookup would require extrapolation 367325588.004024029s into the past.  Requested time 1301326755.953867912 but the earliest data is at time 1668652343.957891941, when looking up transform from frame [base_link] to frame [map]

1668652343是当前时间的,1301326755是数据集中的时间。 目前未解决

软件所的数据集运行


不需要在任何地方设置use_sim_time,如果出现时间戳问题,关掉一切节点,重新开始roscore。launch里不能加<param name="/use_sim_time" value="true" />,否则cartographer一直阻塞。

问题:

  1. scan话题里的坐标系是laser,这是驱动程序决定的。但是tf里的坐标系变成了laser_mount_link,到了tf_bridge_.LookupToTracking那里卡住了,即使手动改了源码也不行。

  2. 坐标系名称带了/,这个其实在cartographer里会被解决,但是习惯上不要加上。

  3. 也无法获得mapbase_link的转换。

  4. tfecho map odom会发现位姿跳变极大, 还没搞清楚, 不是是否和时间戳有关

参考:
TF_OLD_DATA 问题
TF_OLD_DATA的另一种原因