レーザーセンサー付き移動ロボットの作成
概要
ROSのGazeboを使ったシミュレーションでは、ロボットのモデルデータをURDFで作成します。
URDFでロボットモデルの作成では、移動ロボットのモデルを作成して動かしましたが、今回は、レーザーセンサー付きのモデルを作成してみます。
このページのパッケージのソースは、https://github.com/joe-ash/tbotにアップしてあります。
作成するロボットの仕様
作成するロボットは、Turtlebot3のような、レーザーレンサー付きの差動2輪+補助輪型の移動ロボットとします。ロボットの上に箱型のレーザーセンサーを取り付けてあります。
ロボットの形状は、Turtlebot3のBurgerと大きさや重さはほぼ同じで、幅 138mm、長さ 178mm、高さ 192mm、重さ 1kgとなります。平面図、正面図、側面図を描いてみました。x軸方向が前となっています。
モデルの構造としては、下記のようになります。
base_footprint 基準位置(車軸の中心の地上面)
+- base_link box ボディ(箱型車軸部)
+- body_link cylinder ボディ(円筒本体部)
+- wheel_r cylinder 右車輪
+- wheel_l cylinder 左車輪
+- caster_0 sphere 補助輪
+- lidar_0 box レーザーセンサー
ロボットの作成
ビルド環境の作成
URDFのビルド用の環境を作成します。
$ cd ~/catkin_ws/src
$ catkin_create_pkg tbot urdf xacro
$ cd tbot
$ mkdir urdf worlds launch config
ファイル構成
環境ができたら、urdfフォルダとlaunchフォルダに各ファイルを設置します。
- tbot/urdf/tbot.urdf.xacro
tbot.urdf.xacroファイルは、ロボットモデルのXacroファイルです。下記にあるcommon.urdf.xacro、wheel.urdf.xacro、caster.urdf.xacro、lidar.urdf.xacroの4つのヘッダファイルを利用しています。ヘッダファイルのsubというパラメータは、XacroがURDFに展開した時にユニークな名前にするためのサブIDです。左右であればlrの文字を指定しても構いませんし、0,1,2,3のような連番を付加しても構いません。
リンクには、ロボットの基準位置となる原点を表すリンクがあります。一般的には、base_linkと言う名前で定義されることが多いですが、差動2輪型の移動ロボットの場合、駆動輪の中心の地上部分を基準にすることが多いので、base_footprintと言う名前で作成しています。
ロボットのデータは、x軸方向に進行するように、linkデータとjointデータの設定を行っています。
ロボットの各部品は、linkタグによって定義します。
visualタグで、大きさや色などの物理的なデータを定義します。色は、common.urdf.xacroを参照するようにしているため、materialタグにWhiteと色名で設定してあります。gazeboは、visualの色を参照しないので、gazeboで使う色はvisualタグとは別のgazeboタグにも、Gazebo/Whiteと定義する必要があります。
inertiaタグの値は、要素の形によって決まるため、Xacroのマクロを使って計算しています。
各リンクには、上位リンクとの位置関係と関節などの接続関係を表すジョイントが必要ですので、jointタグによって定義します。
一番下のdifferential_drive_controllerの設定は、差動2輪型のロボットの動作を定義するための設定です。ロボットやモーターを購入すると、その機種に合ったパラメータが提供されていると思いますので、ここでは説明を省略します。tbotは、大きさと重さはTurtlebot3 Burgerに合わせていますので、Turtlebot3 Burgerの設定を参考にして設定しています。変更する場合は、上記リンクにあるGazeboプラグインの説明を参照してください。
- tbot/urdf/common.urdf.xacro
common.urdf.xacroファイルは、各種ロボットで共通に利用可能な、定数の設定や、慣性の計算や、色の指定などを行います。慣性の計算は、箱型、円柱型、球型の物体に対して、大きさなどの引数を渡すことで計算できます。色の指定はrgbaでなく、色名で指定可能になるため、xacroのソースファイルが見やすくなるのと、複数の部品の色を同時に変えることができるようになります。
- tbot/urdf/wheel.urdf.xacro
wheel.urdf.xacroファイルは、駆動輪のホイールの定義を行います。通常、右と左で同じ車輪を使うことが多いので、定義が半分になるだけでなく、同じホイールを使う他のロボットとも共通に利用することもできます。
車輪はURDFのcylinder要素として作成します。cylinder要素はx軸で回転するように作成されるため、x軸方向に進むようにx軸のロール角を90度(π/2radian)回転します。
- tbot/urdf/caster.urdf.xacro
caster.urdf.xacroファイルは、補助輪用のキャスターの定義を行います。補助輪は、Gazeboの動作上あまり重要でないため、球形にしてあります。2軸キャスターであれば、2個の円柱をジョイントで繋ぐべきだと思います。
- tbot/urdf/lidar.urdf.xacro
lidar.urdf.xacroファイルは、レーザーセンサーの定義を行います。レーザーセンサーの照射範囲が分かりやすいように、visualizeをtrueに設定してあります。
レーザーセンサーの向きは、前方向になります。レーザーセンサーは、後方向や横方向に向けて設置することもあるので、向きもパラメータで設定できるようにした方が良いと思います。
- tbot/launch/tbot.launch
tbot.launchファイルは、Gazebo内にロボットモデルを表示するための起動用launchファイルです。
Gazeboの起動は、gazebo_rosパッケージに含まれるempty_world.launchを利用しています。
robot_descriptionでは、Xacroを使ってurdfデータを生成していますので、起動には時間がかかりますが、常に最新のデータを参照されるようにしています。
最後に、urdf_spawnerによって、モデルをgazeboに登録しています。
URDFの作成、確認
以下のコマンドでXacroを起動し、URDFを作成し確認します。
Kineticの場合は、--inorderオプションを追加しないとワーニングエラーになります。Xacroの文法は、よく変更があるため、バージョンが異なるとエラーになる可能性があります。
$ cd ~/catkin_ws/src/tbot/urdf
$ rosrun xacro xacro --check-order tbot.urdf.xacro
$ rosrun xacro xacro tbot.urdf.xacro > tbot.urdf
$ check_urdf tbot.urdf
実行すると、tbot.urdfというURDFファイルができます。ファイルを見ると、Xacroによって、インクルードファイルの内容が展開されているのが分かります。
ロボットの表示
Gazeboで表示
Gazeboを起動し、作成したロボットを表示します。
$ roslaunch tbot tbot.launch
下記のような画面が表示されます。
キーボードでロボットを操作
gazeboのプラグインに/cmd_velにTwistメッセージを送ればロボットを操作できる仕様になっています。
別端末を開き、teleop_twist_keyboardを起動すると、作成したロボットを操作することができます。
$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py
キー操作の方法は端末上に表示されますので、説明に従って操作してください。
TurtlebotのWorldファイルの参照
周囲に壁などがある方が、レーザーセンサーの照射範囲が分かりやすいので、turtlebot3_gazeboパッケージのturtlebot3_worldというWorldデータを参照して表示するように設定します。
ファイル構成
- tbot/launch/tbot_turtle.launch
tbot_turtle.launchファイルは、turtlebot3のworldファイルに、作成した移動ロボットを表示するための起動用launchファイルです。
Gazeboで表示
launchファイルを使ってGazeboを起動し、作成したロボットを表示します。
$ roslaunch tbot tbot_turtle.launch
下記のような画面が表示されます。
rvizでレーザーセンサーの値を表示
ファイル構成
- tbot/launch/tbot_rviz.launch
tbot_rviz.launchファイルは、office01.worldファイルに、作成したレーザーセンサー付きロボットをgazeboとrvizで表示するための起動用launchファイルです。
rvizで表示するためには、joint_state_publisherと、robot_state_publisherを起動し、tfデータを渡す必要があります。
- tbot/config/tbot.rviz
tbot.rvizファイルは、rvizの設定ファイルです。launchファイルで設定していますので、設定を保存すると上書きされます。configフォルダは、あらかじめ作成しておく必要があります。GITリポジトリをダウンロードして利用すれば、次のrvizでの設定操作を省くことができます。
rvizの設定と表示
launchファイルを使ってGazeboとrvizを起動し、作成したロボットを表示します。
$ roslaunch tbot tbot_rviz.launch
初回起動時は、rvizの初期設定を行っていませんので、エラーが表示され、何も表示されません。rvizの設定は、下記の方法で行います。
・Displaysの「Add」で「RobotModel」を追加
・Displaysの「Global Options」の「Fixed Frame」を「base_footprint」に設定
モデルのルートリンクの値は「base_link」などモデル毎に異なる
・Displaysの「Add」で「LaserScan」を追加
・Displaysの「LaserScan」の「Topic」を「/scan」に設定
レーザーセンサーが読み取った値が、赤色の点で表示される
・Displaysの「Add」で「Map」を追加
・Displaysの「Map」の「Topic」を「/map」に設定
「Map」は、slamで地図作成する場合に必要
・Viewsの「Type」を「TopDownOrtho」に設定
・ViewsパネルとTimesパネルを非表示
・表示画面をロボットと地図が見易い状態に変更
設定が終わったら「File」メニューの「Save Config」で設定ファイルに保存します。launchファイルは、設定ファイル(tbot/config/tbot.rviz)を参照して起動するように設定してありますので、次回起動時からは、保存時の画面で起動されます。
rqt_graphで確認すると、下記のような画面になります。
rqt_graphを見てみると、gazeboとrvizとpublisherの関係が分かります。rvizは、/scanトピックを購読しているのに表示されていませんが、HideのDebugのチェックを外すと表示されますが、Debug関連のノードも多数表示されますので、見難くなります。