ROS gmapping のパラメータ解説

ROSのパッケージgmappingを使用して、地図を作成してみようと思います。

このlaunchファイルはgmappingをクローンしてきたときにデフォルトで入っているlaunchファイルになります。このファイルを使用するロボットやセンサに合わせていい感じに調整すると、綺麗な地図が出来上がります。

それぞれのパラメータについて、一つ一つ見ていきましょう。

<launch>
    <param name="use_sim_time" value="true"/>
    <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
        <remap from="scan" to="base_scan"/> <param name="map_update_interval" value="5.0"/>
        <param name="maxUrange" value="16.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="srr" value="0.1"/>
        <param name="srt" value="0.2"/>
        <param name="str" value="0.1"/>
        <param name="stt" value="0.2"/>
        <param name="linearUpdate" value="1.0"/>
        <param name="angularUpdate" value="0.5"/>
        <param name="temporalUpdate" value="3.0"/>
        <param name="resampleThreshold" value="0.5"/>
        <param name="particles" value="30"/>
        <param name="xmin" value="-50.0"/>
        <param name="ymin" value="-50.0"/>
        <param name="xmax" value="50.0"/>
        <param name="ymax" value="50.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"/>
    </node>
</launch>

基本的なgmappingのパラメータ

~inverted_laser (string, default: "false")
スキャンの回転方向を反転させるかどうか。通常は反時計回り(CCW)の順番でレーザのスキャンデータが格納されている。
時計回り(CW)の場合にはtrueにセットすればよい。

~throttle_scans (int, default: 1)
処理の頻度.デフォルとではスキャン毎に処理を行なう。
例えば5にセットすると、5スキャンに1回のみ処理を行なう。。。と思う。多分。

~base_frame (string, default: "base_link")
ロボットのベースリンク座標系の指定。

~map_frame (string, default: "map")
マップ座標系の指定。

~odom_frame (string, default: "odom")
オドメトリ座標系の指定。

~map_update_interval (float, default: 5.0)
マップをアップデートする頻度。単位は秒。

~transform_publish_period (float, default: 0.05)
tfを発行する頻度[sec]。
自己位置推定を行いながら地図生成を行なうため、gmappingは map -> odom フレームのtfを発行する。

LiDARのパラメータ

~maxUrange (float, default: 80.0)
mappingを行なうのに使われるscanの最大検出距離。
後述するmaxRangeはLiDARの最大検出距離。

~maxRange (float)
LiDARの最大検出距離。
maxUrange < センサの最大検出距離 <= maxRange となるように設定する。

~sigma (float, default: 0.05)
マッチングを行なう際の標準偏差。(sell)
loop closureのマッチングの誤差に関するパラメータか。

The sigma used by the greedy endpoint matching

~kernelSize (int, default: 1)

  • The kernel in which to look for a correspondence

~lstep (float, default: 0.05)

  • The optimization step in translation

~astep (float, default: 0.05)

  • The optimization step in rotation

~iterations (int, default: 5)

  • The number of iterations of the scanmatcher

~lsigma (float, default: 0.075)
スキャンマッチングを行なう際のレーザ1本の標準偏差。

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

~lskip (int, default: 0)
scanの点を読み飛ばすことができる。(処理の低減か)
0にセットすると、すべてのscanを使用する。
Number of beams to skip in each scan. Take only every (n+1)th laser ray for computing a match (0 = take all rays)

~minimumScore (float, default: 0.0)

  • Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose estimates in large open spaces when using laser scanners with limited range (e.g. 5m). Scores go up to 600+, try 50 for example when experiencing jumping estimate issues.

ロボットの動作モデルのパラメータ

~srr (float, default: 0.1)
オドメトリの誤差。平行移動に起因する平行移動の誤差。

~srt (float, default: 0.2)
オドメトリの誤差。回転移動に起因する平行移動の誤差。

~str (float, default: 0.1)
オドメトリの誤差。平行移動に起因する回転移動の誤差。

~stt (float, default: 0.2)
オドメトリの誤差。回転移動に起因する回転移動の誤差。

動作モデルについては(それ以外にも、slamの大概の事は)、確率ロボティクスに詳しく書いてあるので、一読すると良い。

パーティクルフィルタのパラメータ

~linearUpdate (float, default: 1.0)
並行移動での観測の間隔[m]。
同一箇所で何度も観測を行なうと、パーティクルの尤度に偏りが生じてしまうため、一定距離以上移動した後に次の観測を行なう。

~angularUpdate (float, default: 0.5)
角度方向の観測の間隔[rad]。

~temporalUpdate (float, default: -1.0)
観測の時間の間隔[sec]。
上記のlinearUpdate,angularUpdate分ロボットが動いていなくとも、この時間経過したら観測を行なう。
マイナスにセットすると、時間基準での観測は行わない。

~resampleThreshold (float, default: 0.5)
パーティクルフィルタのリサンプリングの閾値。
AMCLでは,パーティクルフィルタのリサンプルを行う際にNeffという値に基づいてリサンプリングを行う。
$$Neff=\frac{1}{\sum_{i=0}^N(\omega_i)^2}$$
上式のNはパーティクル数、ωiは各パーティクルの尤度である。
Neffはパーティクルの尤度の2乘の積和を分母に持った値で,リサンプリング直後のパーティクルの尤度に差がついていない状態ではNeffの値はNとなる。パーティクル尤度に差がつくにしたがってNeffの値は下がっていき。最終的に1に漸近する。
resampleThresholdはNeffの初期値Nに対する割合を示しており、その値を下回った時点でresampleが行われる。

~particles (int, default: 30)
パーティクルの数。
amclはパーティクル数が分散に応じて可変であったが、gmappingでは固定。

mapのパラメータ

~xmin (float, default: -100.0)
マップのサイズ。x方向の下限。

~ymin (float, default: -100.0)
マップのサイズ。y方向の下限。

~xmax (float, default: 100.0)
マップのサイズ。x方向の上限。

~ymax (float, default: 100.0)
マップのサイズ。y方向の上限。

~delta (float, default: 0.05)
マップの分解能。グリッドの一辺の長さ[m]。

~occ_thresh (float, default: 0.25)
セルが障害物かそうでないかを決定する閾値。
グリッドセルで表現された各セルの値がこの値以上であれば障害物であると判断する。

  • Threshold on gmapping’s occupancy values. Cells with greater occupancy are considered occupied (i.e., set to 100 in the resulting sensor_msgs/LaserScan). New in 1.1.0.

尤度場の計算について

~llsamplerange (float, default: 0.01)

  • Translational sampling range for the likelihood

~llsamplestep (float, default: 0.01)

  • Translational sampling step for the likelihood

~lasamplerange (float, default: 0.005)

  • Angular sampling range for the likelihood

~lasamplestep (float, default: 0.005)

  • Angular sampling step for the likelihood