问题
1.cartographer2D建图 数据包建图和实际场景建图差别很大,为什么会出现不一样的情况?具体见后续描述
2.数据包建图,无tf的情况,tf关系是否必须和实际建图一致?(个人感觉可以不一致)
3.odom和base_footprint的变换关系需要定义吗?从turtlebot中的文件里并未找到此定义关系(个人感觉不用定义)
问题比较多,感谢🙏
数据包建图launch文件
lua文件和实际场景建图文件一致,launch文件去掉了minimal.launch,加入了cartographer_occupancy_grid_node,playbag和/use_sim_time
<launch>
<!--<include file="$(find turtlebot_bringup)/launch/minimal.launch" />--> <!--无tf时加入-->
<!-- bag的地址与名称 -->
<arg name="bag_filename" default="/home/mina/bagfiles/17.bag"/>
<!--<node pkg="tf2_ros" type="static_transform_publisher" name="base_linktolaser"
args="0 0 0.95 0 0 0 base_link laser" />--> <!--无tf时加入-->
<!-- 使用bag的时间戳 -->
<param name="/use_sim_time" value="true" />
<!-- 启动cartographer -->
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory
$(find cartographer_turtlebot)/configuration_files
-configuration_basename turtlebot_rplidar_lidar_2d.lua"
output="screen">
<remap from="scan" to="/scan" />
<!--<remap from="imu" to="/imu_out" />-->
</node>
<!-- 生成ros格式的地图 -->
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<node name="flat_world_imu_node" pkg="cartographer_turtlebot"
type="cartographer_flat_world_imu_node" output="screen">
<!--<remap from="imu_in" to="/mobile_base/sensors/imu_data_raw" />-->
<remap from="imu_in" to="/mobile_base/sensors/imu_data_raw" />
<remap from="imu_out" to="/imu" />
</node>
<!-- 启动rviz -->
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_turtlebot
)/configuration_files/demo_turtlebot.rviz" />
<!-- 启动rosbag -->
<node name="playbag" pkg="rosbag" type="play"
args="--clock $(arg bag_filename)" />
</launch>
一、实地建图并录制数据包
turtlebot2
rplidar A2
单电脑,键盘控制
1. 建图效果
走了一圈(这里激光雷达放的地方感觉不大精准,就大致以kobuki底盘为中心,往上估计95cm的中心处)
2.rqt_graph
3. 数据包信息
二、数据包建图【1】
1.数据包信息(/mobile_base/sensors/imu_data_raw,/odom,/scan,/tf,/tf_static)
参考cartographer_turtlebot_demo.bag数据包信息,录制了如下几个话题
2.建图效果
为何与实地地图相差这么大?不解
3.rqt_graph
4.view_frames
因为是电脑键盘控制,所以会出现两种tf
5.警告信息
[ WARN] [1649301682.964945912, 1648108208.540527587]: W0407 11:21:22.000000 4516 tf_bridge.cc:52] Lookup would require extrapolation into the past. Requested time 1648108207.806168100 but the earliest data is at time 1648108207.824011778, when looking up transform from frame [laser] to frame [gyro_link]
[ WARN] [1649301785.494751551, 1648108311.071525867]: W0407 11:23:05.000000 4516 tf_bridge.cc:52] Lookup would require extrapolation into the past. Requested time 1648108293.300401000 but the earliest data is at time 1648108299.882438888, when looking up transform from frame [odom] to frame [gyro_link]
[ WARN] [1649301778.300297667, 1648108303.875932261]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.64811e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
Warning: TF_OLD_DATA ignoring data from the past for frame odom at time 1.64811e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
at line 277 in /tmp/binarydeb/ros-melodic-tf2-0.6.5/src/buffer_core.cpp
做了一些解决尝试,仍未解决,似乎这些出现都是在turtlebot没有运动的时候,但闪的太快也不大确定
其中第三个warn链接里的,见下图,rviz中的reset点了仍无法解决,另外一个见view_frames没大理解什么意思。
三、数据包建图【2】(imu)
直接使用/imu,去除节点flat_world_imu_node,不使用mobile_base/sensors/imu_raw_data
1.数据包信息
/odom,/imu,/scan,/tf,/tf_static
2.建图效果
更加糟糕了,完全不如mobile_base/sensors/imu_raw_data经过flat_world_imu_node节点后得到的imu信息
3.rqt_graph
四、数据包建图【3】(无tf)
主要是去掉了tf(询问得知是说之前tf有map,carto建图自己也会发map的tf,这时候坐标就会跳变了,因为有2个map的tf,但为什么cartographer_turtlebot_demo.bag里有tf就行的通的呢?)
launch文件中加入
<include file="$(find turtlebot_bringup)/launch/minimal.launch" />
<node pkg="tf2_ros" type="static_transform_publisher" name="link_broadcaster"
args="0 0 0.95 0 0 0 base_link laser" />
1. 数据包信息(mobile_base/sensors/imu_raw_data,/scan,/odom)
1)建图效果1
这次和实地建图差不多
2)建图效果2
但这次就相差很大了
而后的几次都是出现各种各样与实地建图不一样的情况
2. rqt_graph
图中保留了<include file="$(find turtlebot_bringup)/launch/minimal.launch" />
的节点信息(里面包含了turtlebot的tf信息)
3.view_frames
4. 警告信息
与之前有tf的情况相比,警告变得单一了,但是不解的是,给的是和实地场景跑的一样的tf,为何还会出现odom source frame不存在的问题呢?(不知是否在实地跑turtlebot时,就存在这个警告,被自己忽略了)
有尝试通过static_transform在launch文件中加入odom和base_footprint的坐标一致的信息(没找到odom和base_footprint的变换具体信息,个人感觉就不用添加),警告是没有了,图仍然和实地跑不一致。
[ WARN] [1649397381.171347593, 1648108215.742327498]: W0408 13:56:21.000000 4406 tf_bridge.cc:52] "odom" passed to lookupTransform argument source_frame does not exist.