ROSのSLAMを使った地図作成とナビゲーションでは、TurtleBot3のパッケージに入っているlaunchファイルで地図作成とナビゲーションを行いました。今回は、URDFから自分で作成した移動ロボットを使って、地図作成とナビゲーションを行ってみます。
地図作成には、OpenSlamのgmappingパッケージを使います。
ロボットモデルは、センサー付き移動ロボットの作成で作成した移動ロボットを使います。
このページのパッケージのソースは、https://github.com/joe-ash/tbotにアップしてあります。
地図作成は、モデルとセンサーの情報をもとに、SLAMという技術を使って作成します。SLAMとは、Simultaneous Localization and Mappingの略で、自己位置推定を行いながら地図作成を行うことです。gmappingで作成した地図データは、map_serverパッケージのmap_saverで、地図ファイルに出力することができます。map_serverは、地図を管理するためのパッケージで、地図ファイルの作成だけでなく、ナビゲーション時に地図データの提供も行っています。今回は、実機はありませんので、gazeboシミュレータでの実行のみ行います。
ロボットモデルは、センサー付き移動ロボットの作成で作成したtbotを使うため、tbotパッケージのlaunchフォルダに起動用のlaunchファイルを作成します。Worldデータは、Turtlebot3のワールドデータを使いますので、ロボットの実行は、tbot_turtle.launchを利用します。
$ roslaunch tbot tbot_turtle.launch
地図作成には、Gmappingを使いますので、Gmappingを起動するためのlaunchファイルを作成します。
$ cd ~/catkin_ws/src/tbot/launch
$ vi tbot_slam.launch
<launch>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="base_frame" value="base_footprint"/>
<param name="odom_frame" value="odom"/>
<param name="map_frame" value="map"/>
<param name="map_update_interval" value="1.0"/>
<param name="linearUpdate" value="1.0"/>
<param name="angularUpdate" value="0.2"/>
<param name="temporalUpdate" value="1.0"/>
<param name="maxUrange" value="3.0"/>
<param name="maxRange" value="8.0"/>
<param name="xmin" value="-10.0"/>
<param name="ymin" value="-10.0"/>
<param name="xmax" value="10.0"/>
<param name="ymax" value="10.0"/>
<param name="delta" value="0.05"/>
<param name="particles" value="100"/>
<param name="minimumScore" value="50"/>
</node>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node pkg="rviz" type="rviz" name="rviz" required="true"
args="-d $(find tbot)/config/tbot_slam.rviz"/>
</launch>
gmappingのパラメータは、ROS wiki gmappingの説明を参考に設定します。
base_frame | ロボットの基準となるリンクの座標系フレーム |
---|---|
map_frame | 地図の基準となる座標系フレーム |
odom_frame | ロボットの移動量を表すオドメトリの基準となる座標系フレーム |
map_update_interval | 地図の更新間隔(秒) |
linearUpdate | スキャンを実行する距離 |
angularUpdate | スキャンを実行する回転角 |
temporalUpdate | スキャンを実行する時間 |
maxUrange | センサーの最大利用可能範囲 maxUrange < 実際のセンサーの最大範囲 <= maxRange |
maxRange | センサーの最大範囲(実際のセンサーの最大範囲) |
xmin | 地図サイズ(m) |
ymin | 地図サイズ(m) |
xmax | 地図サイズ(m) |
ymax | 地図サイズ(m) |
delta | 地図の解像度(占有グリッドあたりのm値) |
particles | フィルター内の粒子数 |
minimumScore | スキャンマッチングの結果を考慮するための最小スコア ジャンプ推定問題が発生したときは50を設定 |
launchファイルを作成したら、起動して、rvizの設定を行います。
$ roslaunch tbot tbot_slam.launch
rvizの設定は、下記の方法で行います。
・Displaysの「Add」で「RobotModel」を追加
・Displaysの「Global Options」の「Fixed Frame」を「base_footprint」に設定
・Displaysの「Add」で「LaserScan」を追加
・Displaysの「LaserScan」の「Topic」を「/scan」に設定
・Displaysの「Add」で「Map」を追加
・Displaysの「Map」の「Topic」を「/map」に設定
・Viewsの「Type」を「TopDownOrtho」に設定
・ViewsパネルとTimesパネルを非表示
・表示画面をロボットと地図が見易い状態に変更
設定が終わったら「File」メニューの「Save Config」で設定ファイルに保存します。
一度だけ保存しておけば、次回からはrvizの設定をする必要はありません。
rqt_graphで確認すると、下記のような画面になります。
地図を作成するには、キーボード操作で、地図を作成したい場所をロボットを移動させる必要があります。
$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py
地図が完成したら、別のウインドウを開き、下記のコマンドで地図を保存します。
$ mkdir ~/maps
$ rosrun map_server map_saver -f ~/maps/turtle_map
turtle_mapは、地図名ですので、任意の名前を指定できます。
mapsフォルダの中を見ると、下記の2つのファイルが作成されています。
yamlファイルは、オブジェクトを文字列化したデータ形式で、設定ファイルなどで使われています。インデントを使って階層構造を表したテキストファイルです。
TurtleBot3のパラメータをコピーして設定したので、それなりに動きますが、地図のずれもあったり、応答性も悪いです。ですから、もっと、パラメーターの調整が必要そうです。