(二) slam_gmapping节点和所有参数

slam_gmapping节点在gmapping包里面,它的节点信息如下:

它获取sensor_msgs/LaserScan的消息,然后用来建图。/slam_gmapping一边建图一边将地图数据发布到map话题,如果用rviz订阅map话题,我们就能看到建图的过程了.

话题和服务

entropy话题实际是simple_gmapping/entropy,发布机器人姿态分布熵的估计

服务dynamic_map(nav_msgs/GetMap),调用该服务可以获取地图数据,可以用rosservice call试验

需要的tf变换:

  • laser → base_link, 一般是固定的变换,使用static_transform_publisher节点实现
  • base_link → odom, 由里程计系统提供

运行导航程序后,获得tf变换关系:

slam_gmapping的参数

gmapping包生成三个节点,分别为slam_gmappingslam_gmapping_replay及一个测试用的节点。我们主要看slam_gmapping节点,它用到了很多参数,蓝色的是影响CPU性能的

小强目前所用参数只有map_update_interval改为1,粒子数为50,激光评分为140,其他都是默认的

gmapping wrapper参数

  • throttle_scans : [int,默认1] 当接收到n个(默认1个)激光扫描数据,就进行一次更新
  • base_frame: [string, default:”base_link”] 机器人上用的坐标系frame_id
  • map_frame: [string,default:”map”] 机器人地图所用的frame_id
  • odom_frame: [string,default:”odom”] 里程计坐标系的frame_id
  • map_update_interval : [float,default:5.0] 两次更新地图的间隔,降低参数会更新occupancy grid更频繁,但增大CPU占用

Laser Parameters

  • maxRange [double] 雷达扫描的最大有效距离,超过这个数值的扫描会忽略。

  • maxUrange [double,default: maxRange] 用于建图的最大可用扫描距离,因为激光
    雷达的测量距离越远,测量数据的误差越大, 考虑扫地机器人为室内机器人, 因
    maxUrange尽量设置小一些。

  • sigma [float, default: 0.05] The sigma used by the greedy endpoint matching。endpoint匹配标准差,计算score时的方差

  • kernelSize [int,default: 1] The kernel in which to look for a correspondence, search window for the scan matching process. 用于查找对应的kernel size, 主要用在计算score时搜索框的大小

  • lstep [float,default: 0.05] initial search step for scan matching (linear).平移优化步长

  • astep [float,default: 0.05] initial search step for scan matching (angular).旋转优化步长

  • iterations [int, default: 5] 扫描匹配的迭代步长的细分数量,最终距离和角度的匹配精度分别为lstep * 2 ^ (-iterations)astep * 2 ^ (-iterations),这个不是ICP迭代次数,而是用在ScanMatcher::optimize里的搜索步长范围

  • lsigma [float, default: 0.075] The sigma of a beam used for likelihood computation. 用于扫描匹配概率的激光标准差

  • ogain [float, default: 3.0] Gain to be used while evaluating the likelihood, for smoothing the resampling effects. 似然估计为平滑重采样影响使用的gain. 对应函数normalize()中的m_obsSigmaGain,用于粒子权重归一化

  • lskip [int, default: 0]计算似然时,跳过的激光束。0表示所有的激光都处理,如果计算压力过大,可以改成1。源码中的逻辑相当于这样:

1
2
3
4
5
6
7
8
9
10
// 令 lskip 为5, 50为激光束的个数
unsigned int skip=0;
for (unsigned int i=0; i<50; i++)
{
skip++;
skip=skip > 5 ? 0 : skip;
if (skip)
continue;
cout << i << " ";
}

结果为 5 11 17 23 29 35 41 47

  • minimumScore [float, 默认 0.0] 最小匹配得分,一定要自定义,它决定了你对激光的一个置信度,越高说明你对激光匹配算法的要求越高,激光的匹配也越容易失败而转去使用里程计数据,而设的太低又会使地图中出现大量噪声。为获得好的扫描匹配输出结果,用于避免在大空间范围使用有限距离的激光扫描仪(如5m)出现的jumping pose estimates问题。当Scores高达600+,如果出现了该问题可以考虑设定值50。
它取决于激光雷达的测量范围 、角度分辨率、测量精度以及环境特征。

Others:

  • linearUpdate: [float,默认1] 机器人走过多少米,gmapping才处理雷达scan数据

  • angularUpdate: [float,默认0.5] 机器人转过多少弧度,gmapping才处理雷达scan数据

  • temporalUpdate: [float,默认-1] 两次雷达scan数据之前的等待时间,小于0则不启用这个功能

  • resampleThreshold [float,default: 0.5] 粒子重新采样的门槛值,越大表示重新采样越频繁

  • particles : [int,默认30] 决定gmapping算法中的粒子数,每个粒子代表了机器人走过的可能的trajectory,因为gmapping使用的是粒子滤波算法,粒子在不断地迭代更新,所以选取一个合适的粒子数可以让算法在保证比较准确的同时有较高的速度。 看gmapping论文,一般设置为30,高难度地图用80,我一般用50个,大概对应CPU占比25%

运动模型参数 (高斯噪声模型的所有标准偏差)

  • srr [float, default: 0.1] linear noise component (x and y),Odometry error in translation as a function of translation (rho/rho) 线性运动造成的线性误差的方差

  • srt [float, default: 0.2] linear -> angular noise component,Odometry error in translation as a function of rotation (rho/theta). 线性运动造成的角度误差的方差 (rho/theta)

  • str [float, default: 0.1] angular -> linear noise component,Odometry error in rotation as a function of translation (theta/rho). 旋转运动造成的线性误差的方差 (theta/rho)

  • stt [float, default: 0.2] angular noise component (theta),Odometry error in rotation as a function of rotation (theta/theta). 旋转运动造成的角度误差的方差 (theta/theta)

Likelihood sampling (used in scan matching)

  • llsamplerange [float, default: 0.01] Translational sampling range for the likelihood. 用于似然计算的平移采样距离
  • llsamplestep [float, default: 0.005] Translational sampling step for the likelihood. 用于似然计算的平移采样步长
  • lasamplerange [float, default: 0.01] Angular sampling range for the likelihood. 用于似然计算的角度采样距离
  • lasamplestep [float, default: 0.005] Angular sampling step for the likelihood. 用于似然计算的角度采样步长

地图初始维度和分辨率

  • xmin [double] minimum x position in the map [m]
  • ymin [double] minimum y position in the map [m]
  • xmax [double] maximum x position in the map [m]
  • ymax [double] maximum y position in the map [m]
  • delta [double] 地图分辨率,就是话题map_metadata中的resolution
  • occ_thresh (float, default: 0.25),栅格地图栅格值 (i.e., set to 100 in the resultingsensor_msgs/LaserScan).

参考: ROS Wiki-gmapping