cartographer显示机器人当前位姿

cartographer发布的 map—->odom 转换频率太低

运行cartographer时,可以发现rviz的报警

1
[SubmapsDisplay::update] line_220  Could not compute submap fading: "map" passed to lookupTransform argument target_frame does not exist.

运行程序carto_pose运行时持续报警:

1
Lookup would require extrapolation into the past.  Requested time 1609143852.338626800 but the earliest data is at time 1609143860.343082666, when looking up transform from frame [base_footprint] to frame [map]

但使用rosrun tf tf_echo map odom看不出问题

查看话题carto_pose,发现位姿更新很慢,甚至时间戳不动,显然是获取坐标系关系不及时。使用rqt_tf_tree发现 map --> odom的频率很低。重新启动cartographer建新的地图,发现发布变换的频率会逐步下降,进而影响tf树的其他变换,因为map坐标系是最顶层
频率很低.png

有时频率又突然到10000,话题carto_pose会接受很多消息。

按定义tf频率的是参数pose_publish_period_sec = 5e-3,但是改了改没有见效。

有时重启后,这个现象没有了,频率正常

显示在map中的位姿

通过tf变换获取位姿坐标,获取的位姿频率只有5hz左右,不满足需求。修改源码,

Node构造函数中添加 current_pose_pub = node_handle_.advertise<geometry_msgs::Pose2D>("current_pose", 10);

if (trajectory_data.published_to_tracking != nullptr)部分的最后添加

1
2
3
4
5
6
geometry_msgs::Pose2D pos_now;

pos_now.x = static_cast<double>(stamped_transform.transform.translation.x);
pos_now.y = static_cast<double>(stamped_transform.transform.translation.y);
pos_now.theta = tf::getYaw(stamped_transform.transform.rotation);
current_pose_pub.publish(pos_now);

在我的主机上能达到200Hz

如果provide_odom_frame为true,位姿是odom_framepublished_frame之间的关系(但map和odom一般重合),否则是map_framepublished_frame之间

stamped_transform变量的来源如下