9.2 Gmapping

9.2.1 Gmapping SLAM软件包

Gmapping算法是目前基于激光雷达里程计方案里面比较可靠和成熟的一个算法,它基于粒子滤波,采用RBPF的方法效果稳定,许多基于ROS的机器人都跑的是gmapping_slam。这个软件包位于ros-perception组织中的slam_gmapping仓库中。 其中的slam_gmapping是一个metapackage,它依赖了gmapping,而算法具体实现都在gmapping软件包中,该软件包中的slam_gmapping程序就是我们在ROS中运行的SLAM节点。如果你感兴趣,可以阅读一下gmapping的源代码。

如果你的ROS安装的是desktop-full版本,应该默认会带gmapping。你可以用以下命令来检测gmapping是否安装

apt-cache search ros-$ROS_DISTRO-gmapping

如果提示没有,可以直接用apt安装

sudo apt-get install ros-$ROS_DISTRO-gmapping

gmapping在ROS上运行的方法很简单

rosrun gmapping slam_gmapping

但由于gmapping算法中需要设置的参数很多,这种启动单个节点的效率很低。所以往往我们会把gmapping的启动写到launch文件中,同时把gmapping需要的一些参数也提前设置好,写进launch文件或yaml文件。 具体可参考教学软包中的slam_sim_demo中的gmapping_demo.launchrobot_gmapping.launch.xml文件。

9.2.2 Gmapping SLAM计算图

gmapping的作用是根据激光雷达和里程计(Odometry)的信息,对环境地图进行构建,并且对自身状态进行估计。因此它得输入应当包括激光雷达和里程计的数据,而输出应当有自身位置和地图。 下面我们从计算图(消息的流向)的角度来看看gmapping算法的实际运行中的结构: slam_gmapping 位于中心的是我们运行的slam_gmapping节点,这个节点负责整个gmapping SLAM的工作。它的输入需要有两个:

输入

  • /tf以及/tf_static: 坐标变换,类型为第一代的tf/tfMessage或第二代的tf2_msgs/TFMessage 其中一定得提供的有两个tf,一个是base_framelaser_frame之间的tf,即机器人底盘和激光雷达之间的变换;一个是base_frameodom_frame之间的tf,即底盘和里程计原点之间的坐标变换。odom_frame可以理解为里程计原点所在的坐标系。
  • /scan :激光雷达数据,类型为sensor_msgs/LaserScan

/scan很好理解,Gmapping SLAM所必须的激光雷达数据,而/tf是一个比较容易忽视的细节。尽管/tf这个Topic听起来很简单,但它维护了整个ROS三维世界里的转换关系,而slam_gmapping要从中读取的数据是base_framelaser_frame之间的tf,只有这样才能够把周围障碍物变换到机器人坐标系下,更重要的是base_frameodom_frame之间的tf,这个tf反映了里程计(电机的光电码盘、视觉里程计、IMU)的监测数据,也就是机器人里程计测得走了多少距离,它会把这段变换发布到odom_framelaser_frame之间。

因此slam_gmapping会从/tf中获得机器人里程计的数据。

输出

  • /tf: 主要是输出map_frameodom_frame之间的变换
  • /slam_gmapping/entropystd_msgs/Float64类型,反映了机器人位姿估计的分散程度
  • /mapslam_gmapping建立的地图
  • /map_metadata: 地图的相关信息

输出的/tf里又一个很重要的信息,就是map_frameodom_frame之间的变换,这其实就是对机器人的定位。通过连通map_frameodom_frame,这样map_framebase_frame甚至与laser_frame都连通了。这样便实现了机器人在地图上的定位。

同时,输出的Topic里还有/map,在上一节我们介绍了地图的类型,在SLAM场景中,地图是作为SLAM的结果被不断地更新和发布。

9.2.3 里程计误差及修正

目前ROS中常用的里程计广义上包括车轮上的光电码盘、惯性导航元件(IMU)、视觉里程计,你可以只用其中的一个作为odom,也可以选择多个进行数据融合,融合结果作为odom。通常来说,实际ROS项目中的里程计会发布两个Topic:

  • /odom: 类型为nav_msgs/Odometry,反映里程计估测的机器人位置、方向、线速度、角速度信息。
  • /tf: 主要是输出odom_framebase_frame之间的tf。这段tf反映了机器人的位置和方向变换,数值与/odom中的相同。

由于以上三种里程计都是对机器人的位姿进行估计,存在着累计误差,因此当运动时间较长时,odom_framebase_frame之间变换的真实值与估计值的误差会越来越大。你可能会想,能否用激光雷达数据来修正odom_framebase_frame的tf。事实上gmapping不是这么做的,里程计估计的是多少,odom_framebase_frame的tf就显示多少,永远不会去修正这段tf。gmapping的做法是把里程计误差的修正发布到map_frameodom_frame之间的tf上,也就是把误差补偿在了地图坐标系和里程计原点坐标系之间。通过这种方式来修正定位。

这样map_framebase_frame,甚至和laser_frame之间就连通了,实现了机器人在地图上的定位。

  • /odom

9.2.4 服务

slam_gmapping也提供了一个服务:

  • /dynamic_map: 其srv类型为nav_msgs/GetMap,用于获取当前的地图。

该srv定义如下: nav_msgs/GetMap.srv

# Get the map as a nav_msgs/OccupancyGrid
---
nav_msgs/OccupancyGrid map

可见该服务的请求为空,即不需要传入参数,它会直接反馈当前地图。

9.2.5 参数

slam_gmapping需要的参数很多,这里以slam_sim_demo教学包中的gmapping_demo的参数为例,注释了一些比较重要的参数,具体请查看ROS-Academy-for-Beginners/slam_sim_demo/launch/include/robot_gmapping.launch.xml

<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="base_frame" value="$(arg base_frame)"/> <!--底盘坐标系-->
<param name="odom_frame" value="$(arg odom_frame)"/> <!--里程计坐标系-->
<param name="map_update_interval" value="1.0"/> <!--更新时间(s),每多久更新一次地图,不是频率-->
<param name="maxUrange" value="20.0"/> <!--激光雷达最大可用距离,在此之外的数据截断不用-->
<param name="maxRange" value="25.0"/> <!--激光雷达最大距离-->
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="minimumScore" value="200"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<param name="linearUpdate" value="0.5"/>
<param name="angularUpdate" value="0.436"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="80"/>
<param name="xmin" value="-25.0"/>
<param name="ymin" value="-25.0"/>
<param name="xmax" value="25.0"/>
<param name="ymax" value="25.0"/>
<param name="delta" value="0.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>

演示截图

gmapping算法演示效果图如下:

results matching ""

    No results matching ""