阅读gmapping参数文档发现表达上存在歧义,为了设置更好的建图参数,构建适合用于导航的栅格地图,对存在歧义的参数结合gmapping源码进行解析。

最后提供行室内建图的参数设置策略

以及个人DIY的全向轮小车建图结果展示

PART1 Gmapping参数分析

1.1 ~inverted_laser (string, default: "false")

反转激光雷达数据,默认为false,当激光雷达反向安装时需要

1.2 ~throttle_scans (int, default: 1)

用来求余的除数,越大则忽略的激光数据越多

参考下面的源码容易理解

    laser_count_++;
    if ((laser_count_ % throttle_scans_) != 0)
        return;

默认除数为1,所有的被除数都可以整除,laser_count%throttle_scans余数都为0,所以激光数据会继续运算,不会return进行忽略

1.3 ~base_frame (string, default: "base_link")

机器人的自身坐标系

1.4 ~map_frame (string, default: "map")

建图的全局坐标系

1.5 ~odom_frame (string, default: "odom")

里程计坐标系

1.6 ~map_update_interval (float, default: 5.0)

栅格地图的建图时间间隔,因为耗费计算资源,所以默认值为5s生成一次栅格地图

1.7 ~maxRange (float)

激光雷达的最大探测距离

1.8 maxUrange (float, default: 80.0)

激光雷达的使用距离.源码中默认等于maxRange,与使用说明冲突

    // setting maxRange and maxUrange here so we can set a reasonable default
    // 设置激光雷达的最大观测距离和最大使用距离
    ros::NodeHandle private_nh_("~");
    if(!private_nh_.getParam("maxRange", maxRange_))
        maxRange_ = scan.range_max - 0.01;
    if(!private_nh_.getParam("maxUrange", maxUrange_))
        maxUrange_ = maxRange_;

1.9 ~sigma (float, default: 0.05)

scan-match扫描匹配过程的标准偏差

/*设置匹配的参数*/
void ScanMatcher::setMatchingParameters
    (double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations,  double likelihoodSigma, unsigned int likelihoodSkip)
{
	m_usableRange=urange;						//传感器的使用范围
	m_laserMaxRange=range;						//传感器的最大范围
	m_kernelSize=kernsize;						//kernsize主要用在计算score时搜索框的大小
	m_optLinearDelta=lopt;						//优化时的线性步长
	m_optAngularDelta=aopt;						//优化时的角度步长
	m_optRecursiveIterations=iterations;		//优化时的迭代次数
	m_gaussianSigma=sigma;						//计算socre时的方差
	m_likelihoodSigma=likelihoodSigma;			//计算似然时的方差	
	m_likelihoodSkip=likelihoodSkip;			//计算似然时,跳过的激光束
}

1.10 ~kernelSize (int, default: 1)

扫描匹配过程的搜索窗口大小

1.11 ~lstep (float, default: 0.05)

scan-match中的optimization距离优化步长

1.12 ~astep (float, default: 0.05)

scan-match中的optimization角度优化步长

1.13 ~iterations (int, default: 5)

scan-match中的optimization迭代次数

1.14 ~lsigma (float, default: 0.075)

scan-match的似然计算的标准偏差

1.15 ~ogain (float, default: 3.0)

评估可能性时使用的增益,用于平滑重采样效果

1.16 ~lskip (int, default: 0)

对于一帧激光雷达数据来说 只取每第(n+1)个激光束  这个是相对于scan-match来说的。
如果n等于0 则取每第1帧激光束
如果n等于1 则取每第2帧激光束 也就是说使用的激光束变成原来的1/2
如果n等于2 则取每第3帧激光束 也就是说使用的激光束变成原来的1/3

1.17 ~minimumScore (float, default: 0.0)

scan-matching结果接受的最小得分

1.18 ~srr (float, default: 0.1)

机器人的运动模型的相关的噪声参数,inear noise component (x and y)

1.19 ~srt (float, default: 0.2)

机器人的运动模型的相关的噪声参数,angular noise component (theta)

1.20 ~str (float, default: 0.1)

机器人的运动模型的相关的噪声参数,linear -> angular noise component

1.21 ~stt (float, default: 0.2)

机器人的运动模型的相关的噪声参数,angular -> linear noise component

1.22 ~linearUpdate (float, default: 1.0)

只有当机器人至少移动了linearUpdate米,机器人才会处理新的测量数据,进行scan-match

1.23 ~angularUpdate (float, default: 0.5)

只有当机器人至少旋转了angularUpdate弧度,机器人才会处理新的测量数据,进行scan-match

1.24 ~temporalUpdate (float, default: -1.0)

如果距离上次scan-match时间大于temporalUpdate(秒),则进行scan-match,负值则不更新

 

注意上面三个条件,只要一个符合就会进行scan-match

    // process a scan only if the robot has traveled a given distance or a certain amount of time has elapsed
	/*只有当机器人走过一定的距离  或者 旋转过一定的角度  或者过一段指定的时间才处理激光数据*/
    if (! m_count 
	|| m_linearDistance>=m_linearThresholdDistance 
	|| m_angularDistance>=m_angularThresholdDistance
    || (period_ >= 0.0 && (reading.getTime() - last_update_time_) > period_))
	{

1.25 ~resampleThreshold (float, default: 0.5)

粒子重新采样的阈值。更高意味着更频繁的重采样

1.26 ~particles (int, default: 30)

粒子滤波的粒子个数

1.27 ~xmin (float, default: -100.0)

初始地图x方向最小尺寸

1.28 ~ymin (float, default: -100.0)

初始地图y方向最小尺寸

1.27 ~xmax (float, default: 100.0)

初始地图x方向最大尺寸

1.28 ~ymax (float, default: 100.0)

初始地图y方向最大尺寸

1.29 ~delta (float, default: 0.05)

栅格地图分辨率,每个栅格为边长0.05m的正方形

1.30 ~llsamplerange (float, default: 0.01)

scan-match中似然估计的平移采样范围

1.31 ~llsamplestep (float, default: 0.01)

scan-match中似然估计的平移采样的步长

1.32 ~lasamplerange (float, default: 0.005)

scan-match中似然估计的角度采样范围

1.33 ~lasamplestep (float, default: 0.005)

scan-match中似然估计的角度采样的步长

1.34 ~transform_publish_period (float, default: 0.05)

发布map->odom的坐标转换关系,如果不需要发布坐标变换,则设置为0

1.35 ~occ_thresh (float, default: 0.25)

栅格地图的占用阈值,超过则认为栅格被占用

PART2 室内SLAM的参数选取策略

<launch>
  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
	<param name="throttle_scans" value="1" />
    <param name="base_frame" value="/base_link" />
	<param name="map_frame" value="/map" />
    <param name="odom_frame" value="/odom" />
    <param name="map_update_interval" value="5.0"/>
	<param name="maxRange" value="5.0"/>
    <param name="maxUrange" value="5.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="100"/>
    <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.1"/>
    <param name="angularUpdate" value="0.2"/>
    <param name="temporalUpdate" value="-0.5"/>
    <param name="resampleThreshold" value="0.5"/>
    <param name="particles" value="30"/>
    <param name="xmin" value="-30.0"/>
    <param name="ymin" value="-30.0"/>
    <param name="xmax" value="30.0"/>
    <param name="ymax" value="30.0"/>
    <param name="delta" value="0.05"/>
    <param name="llsamplerange" value="0.05"/>
    <param name="llsamplestep" value="0.05"/>
    <param name="lasamplerange" value="0.005"/>
    <param name="lasamplestep" value="0.005"/>
    <param name="transform_publish_period" value="0.1"/>
  </node>
</launch>

下面进行主要参数设置的说明

2.1 maxRange

设置激光雷达的探测距离,已知激光雷达测量范围是8m,为了避免边缘误差以及减小计算量,设置为5m

2.2 minimumScore

scan-matching结果接受的最小得分,如果scan-match中的optimize位姿优化得分score大于minimumScore,则认为优化成功,接受新的优化位姿作为粒子的位姿,否则使用里程计位姿。

推荐50-600,太高会导致无法优化成功,此处设置为100

2.3 linearUpdate和angularUpdate

激光雷达的发布频率为8Hz,为了充分利用激光数据提高定位优化效果,此处应结合机器人运动速度进行设置,考虑激光频率8Hz,运动速度0.3m/s,0.5rad/s,取0.2s扫描一次,则参数分别设置为0.1m和0.2rad

2.4 xmin,ymin,xmax,ymax

考虑室内环境设置30m*30m范围

PART3 DIY全向轮小车建图效果

测试两个参数linearUpdate和angularUpdate,以它们为变量设计实验表格,对全向轮小车的建图效果进行测试

参数实验一实验二
linearUpdate0.2m/s0.1m/s
angularUpdate0.3rad/s0.2rad/s

实验一和实验二的栅格地图如下

 

 

实验一和实验二建图效果相差不大

但是在实验二的建图过程中,由于0.3m/s的运动速度下更新较快,经常会出现程序卡顿现象,导致定位出现跳跃,但是由于Gmapping的定位优化,定位结果修正后符合实际位置。

实验一建图过程流畅,定位准确,无位姿跳跃情况

PART4 总结

综合参数设置和实际建图效果可知,建图参数设置应当与小车速度,以及CPU计算性能相结合来设置

Logo

为开发者提供学习成长、分享交流、生态实践、资源工具等服务,帮助开发者快速成长。

更多推荐