0x00 hector_mapping简介
hector_mapping是一种SLAM算法,它可以在没有里程计的情况在未知环境下构建当前环境的地图。跟gmapping不同,gmapping建图时需要有里程计信息才行。同时hector_mapping还可以在有IMU模块的平台上运行,这样就具备了俯仰角/横滚角,可以有效的避免因为雷达的晃动导致的建图失败,提高了系统建图的鲁棒性。当然,如果你是在平坦的环境中,且雷达不会任意的晃动,不用IMU模块也是可以的。
hector_mapping正是利用了现代激光雷达的超高扫描频率来预估得到机器人的当前2D位姿信息。虽然它没有提供明确的闭环能力,但是对于很多现实世界的场景已经足够了,该建图算法已经成功的应用于无人机、无人地面车辆、手持式测绘设备等。hector算法的缺点也就是它的优点,就是因为它仅仅依靠激光雷达的扫描数据就可以正常工作,就使它建图和定位效果不如多传感器融合的效果好,但是却可以使它在那些本身就没有里程计信息的机器人上来使用。所以,大家在选择建图算法时就应该根据自己的机器人当前状态来合理选择。
我们可以在机器人的里程计信息正常时使用gmapping算法来建图,如果某些异常情况导致机器人的里程计信息无法正常输出。那么我们就可以切换机器人的建图算法为hector_mapping,这样仍然可以来建图。通过判断机器人当前的不同状态来选择不同的slam算法就可以增加机器人建图的鲁棒性。
0x01 创建stdr_hector_mapping软件包
我们在使用hector_mapping建图时用的是hector_mapping这个软件包提供的功能,我们只不过是配置了节点运行参数而已。因此需要首先确保已经安装好了hector_mapping软件包,使用如下命令来安装:
sudo apt-get install ros-$ROS_DISTRO-hector-slam
接下来就可以在catkin_ws下的src目录下创建stdr_hector_mapping软件包,该软件包是我们用来编写launch文件,存储地图的,具体操作如下图所示:
下面开始在launch目录中编写stdr_hector_mapping.launch启动文件,具体代码如下:
<!--
Copyright: 2016-2018 www.corvin.cn
Author: corvin
Description: In stdr simulator hector mapping.
History:
20180601: initial this file.
-->
<launch>
<arg name="map_scanmatch_frame_name" default="scanmatcher_frame"/>
<arg name="pub_map_odom_transform" default="true"/>
<arg name="scan_queue_size" default="10"/>
<arg name="base_frame" default="/robot0" />
<arg name="odom_frame" default="/robot0" />
<arg name="scan_topic" default="/robot0/laser_0" />
<arg name="map_topic" default="/hector_map" />
<arg name="map_size" default="512" />
<!-- startup stdr simulator with robot0 -->
<include file="$(find stdr_launchers)/launch/server_with_map_and_gui_plus_robot.launch" />
<!-- startup rviz to show hector mapping process -->
<node name="rviz" type="rviz" pkg="rviz" args="-d $(find stdr_hector_mapping)/rviz/config_rviz.rviz" />
<node pkg="hector_mapping" type="hector_mapping" name="stdr_hector_mapping" output="screen">
<remap from="map" to="$(arg map_topic)" />
<!-- Frame names -->
<param name="map_frame" value="/map_static" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="odom_frame" value="$(arg odom_frame)" />
<!-- Map resolution/size/start point -->
<param name="map_resolution" value="0.04"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.2" />
<param name="map_start_y" value="0.2" />
<!-- Map update parameters -->
<param name="map_update_distance_thresh" value="0.45" />
<param name="map_update_angle_thresh" value="0.30" />
<param name="map_pub_period" value="2.2" />
<param name="map_multi_res_levels" value="2" />
<param name="update_factor_free" value="0.4" />
<param name="update_factor_occupied" value="0.9" />
<!-- lidar laser parameters -->
<param name="scan_topic" value="$(arg scan_topic)" />
<param name="laser_min_dist" value="0.06" />
<param name="laser_max_dist" value="4.09" />
<param name="laser_z_min_value" value="-1.0" />
<param name="laser_z_max_value" value="1.0" />
<param name="output_timing" value="false"/>
<param name="scan_subscriber_queue_size" value="$(arg scan_queue_size)"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
<param name="advertise_map_service" value="true" />
<param name="use_tf_scan_transformation" value="true" />
<param name="use_tf_pose_start_estimate" value="true" />
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg map_scanmatch_frame_name)" />
</node>
</launch>
接下来是rviz中显示建图过程的配置文件,该文件可以直接在这里下载config_rviz.rviz.tar.gz,将其下载后解压后放到rviz目录中即可。当把launch文件和rviz配置文件准备好后,就可以来编译该软件包了。具体的操作过程如下图所示:
0x02 启动launch文件开始建图
当准备好launch文件和rviz的配置文件后,下面就可以使用下面的命令来开始建图了:
roslaunch stdr_hector_mapping stdr_hector_mapping.launch
接下来就可以来使用键盘遥控小车移动软件包teleop_twist_keyboard来控制仿真小车四处走动来建地图了,需要注意的是该软件包默认是向/cmd_vel话题发送控制指令,可以使用如下命令来向/robot0/cmd_vel话题发送控制指令遥控stdr中仿真小车的移动:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=robot0/cmd_vel
当使用键盘遥控小车四处走动时,可以在rviz中也可以看到当前环境的地图同时也被扫描记录下来了,如下动图所示:
当使用键盘遥控着小车在地图中走完一圈后,就可以看到地图同步也创建好了,下面是使用hector_mapping创建的完整地图:
在遥控小车四处走动时,需要注意小车的速度不可以过快,否则就会提示如下的错误信息,导致创建的地图出现偏差,一般出现该错误的原因就是雷达出现了剧烈摇晃或数据的不稳。要不然就是在一些无法定位的场景中,例如在一个走廊中,所以hector_mapping适合在那种地形比较复杂的环境中使用。所以还是建议如果有里程计信息的情况下,大家还是使用gmapping算法,在没有里程计的情况下使用hector_mapping:
SearchDir angle change too large
SearchDir angle change too large
0x03 保存创建好的地图
我们需要使用map_server软件包里的map_saver来保存当前的地图,首先需要保证已经安装了map_server软件包,安装命令如下:
sudo apt-get install ros-$ROS_DISTRO-map-server
当安装好map_server后,接下来就可以使用如下命令来保存地图了,在stdr_gmapping的maps目录下执行命令如下:
rosrun map_server map_saver map:=/hector_map -f mymap
为了方便后面快速的保存地图,不用输入这么长的命令,我们可以编写一个脚本saveMap.sh,将上面这条命令放到脚本中,具体如下图所示:
我们保存的地图跟在Rviz中看到的是不一样的,因为最终保存的地图是个灰度图,只有三种状态:黑色的障碍物,白色的自由区域和灰色的未被探索区域:
其实我们保存的地图可以在任意的画图软件中来修改,使其更加的完美。因为在建图过程中,难免会出现一些异常点。这样我们就可以在后期保存了地图后,使用画图软件来修改建好的地图。修改后的地图在后面的自动导航时使用是没有任何问题的。例如上面的这张地图,我们就可以来稍微修改完善一下,如下图所示:
0x04 hector_mapping配置参数的意义
由于该launch文件中配置的参数略多,因此分段来详细介绍各参数意义:
- map_scanmatch_frame_name:发布scanmatcher到map转换的坐标名.
- pub_map_odom_transform:是否发布map到odom的坐标转换.
- scan_queue_size:订阅/scan的队列大小(buffer)。如果有日志回放速度大于实际速度,那这个值应该被设的很高,例如50.
- base_frame:机器人基坐标系的名称。这个坐标系用来定位和激光扫描器数据的改变(transformation).
- odom_frame:里程计坐标系名称,默认是odom.
- scan_topic:hector_mapping订阅的激光雷达的话题名称.
- map_size:要创建的地图的分辨率大小,由于地图是正方形的,所以有(map_size×map_size)个像素面积.该值的选取需要根据实际环境的大小和后面的map_resolution参数来设置,例如实际的环境是15m*15m的空间,如果想要扫描创建的地图分辨率是0.04,那就是说明一个像素点代表实际环境中的4cm,那么要想存储15m*15m的地图,那么该参数map_size设置的大小就应该是15/0.04=375,但是一般不会将地图设置的这么极限刚刚好,都会设置的稍微大点。
- map:这里的remap是为了将hector_mapping输出的地图话题重新映射为/hector_map,因为默认的输出话题是/map,这样会跟stdr仿真器输出的/map话题冲突的,所以需要remap.
- map_frame:地图坐标系名称,通常是map,也就是所谓的全局world坐标系.
- base_frame:机器人基础坐标系的名称.
- odom_frame:里程计坐标系名称,默认是odom,但是一般都是配置成跟base_frame相同的坐标系.
- map_resolution:地图分辨率,单位为m.意思是地图上一个像素代表实际环境中多长距离.
- map_size:要创建地图的分辨率大小.
- map_start_x:map 坐标系定位原点[0.0, 1.0] 的位置到网格上,在x轴方向上,0.5是中间值,其实这算是一个百分比的概念,起始位置占据总长度的百分比.
- map_start_y:map 坐标系定位原点[0.0, 1.0] 的位置到网格上,在y轴方向上.
- map_update_distance_thresh:地图更新的长度阀值,单位m。在一次更新后,平台必须移动这个参数代表的值的距离后,才能再次更新地图.
- map_update_angle_thresh:地图更新的角度阀值,单位rad。在一次更新后,平台必须转动这个参数代表的值的角度后,才能再次更新地图.
- map_pub_period:地图发布的周期,单位秒.
- map_multi_res_levels:地图多级分辨率网格级数.
- update_factor_free:地图更新调节器,用来更新空闲单元的变化。0.5代表没有更改.
- update_factor_occupied:地图更新调节器,用来更新占用单元的变化。0.5代表没有更改.
- scan_topic:设置hector_mapping订阅的激光雷达输出的话题名.
- laser_min_dist:配置激光雷达的输出参数,雷达可以扫描的最近距离,小于该距离的数据都被忽略.
- laser_max_dist:配置激光雷达的输出参数,雷达可以扫描的最远距离,大于该距离的数据都被忽略.
- laser_z_min_value: 系统使用的最低扫描端点,单位m。低于此距离的扫描端点将会被忽略.
- laser_z_max_value:系统使用的最高扫描端点,单位m。高于此距离的扫描端点将会被忽略.
- output_timing:通过ROS_INFO 输出每个laser扫描过程的时序信息,显示调试信息.
- scan_subscriber_queue_size:订阅/scan的队列大小(buffer)。如果有日志回放速度大于实际速度,那这个值应该被设的很高,例如50.
- pub_map_odom_transform:决定是否发布scanmatcher->map的transform的标志.
- advertise_map_service:是否开启发布地图的服务/dynamic_map.
- use_tf_scan_transformation:该参数一般用于调试,如果设置为false,那么将不使用tf对雷达的scan进行坐标转换,这样就只能在地面平坦的地方来建图,如果雷达扫描中有了俯仰角和横滚角那么建图就会失败的.
- use_tf_pose_start_estimate:该参数一般用于调试,如果设置为true,那么就会来预测起始位置,这样就可以跟base_frame重合,当然该参数并不影响建图.
- tf_map_scanmatch_transform_frame_name:用来发布scanmatch到map转换的坐标名.
现在我们已经将所有的hector_mapping有关的参数都简单介绍过了,大家可以根据需要来修改参数并启动仿真来观察效果,多动手调试一下就能对这些参数的调试有个更深刻认识。
0x05 hector_mapping软件包工作流程分析
首先我们可以来看下在建图过程中的节点话题关系图,直接在终端中输入rqt_graph即可打开:
或者可以看下面这个更为简洁一点的图:
这里的/syscommand话题是为了重置建立的地图而设置的,即当向该话题中发布字符串reset时,就会将/hector_map话题中数据清除,重新开始建图,完整命令如下:
rostopic pub -1 /syscommand std_msgs/String “reset”
下面可以来看看这条命令的执行效果,如下动图所示:
0x06 Bibliography & Reference
[1].hector_mapping在ROS Wiki上主页. http://wiki.ros.org/hector_mapping
[2].CSDN上sean_xyz-hector_mapping添加IMU. https://blog.csdn.net/sean_xyz/article/details/67632551
[3].CSDN上sunyoop-ros中的hector_mapping节点详细介绍. https://blog.csdn.net/sunyoop/article/details/78110895
[4].创客智造-ROS与SLAM入门教程-hector_mapping参数介绍. https://www.ncnynl.com/archives/201702/1367.html
[5].中国大学MOOC-机器人操作系统入门-https://sychaichangkun.gitbooks.io/ros-tutorial-icourse163/content/chapter9/9.4.html