Edited at

ROS講座37 gazeboでworldを作成する


環境

この記事は以下の環境で動いています。

項目

CPU
Core i5-8250U

Ubuntu
16.04

ROS
Kinetic

Gazebo
7.14.0

インストールについてはROS講座02 インストールを参照してください。

またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。


概要

gazeboシミュレーターには要素としてロボットを入れることもできますが、環境としての壁や障害物を置くこともできます。これをするにはgazeno特有の書き方(=ROSの書き方とは少し違ったもの)をする必要があります。

今回はworldファイルを記述してgazeboを起動してみます。


worldファイルの記述


worldファイル

ROSではモデルを定義するのにurdfファイルを使用しますが、gazeboではsdfファイルを使用します。形式は違いますが、urdfと同じような設計思想です。本当はもっと複雑なのですが、今回はモデルの呼び出しをするだけなので単純です。


sim3_lecture/worlds/world_test1.world

<?xml version="1.0" ?>

<sdf version="1.5">
<world name="default">
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<name>beer0</name>
<uri>model://coke_can</uri>
<static>true</static>
<pose>2 1 0 0 0 0</pose>
</include>
</world>
</sdf>



  • <include>タグの中ででモデルを呼び出します。初期状態では~/.gazebo/model以下にあるモデルのみを呼び出せます。



  • <uri>model://sun</uri>は呼び出すモデルを参照します。sunground_planeは空のgazeboでもある要素です。とりあえず入れておきましょう。


  • <name>beer0</name>はモデルに名前を付けるタグです。省略可能ですが、同じモデルを複数呼び出すときは必須です。


  • <pose>1 0 0 0 0 0</pose>はモデルの出現位置を決めるタグです。順番にx軸位置、x軸位置、x軸位置、roll回転、pitch回転、yaw回転を表します。回転の単位はdegです。


  • <static>false</static>はモデルを固定するかどうかを決めるタグです。省略するとfalseになります。falseだと物理演算が適用されぶつかれば動きますし、重力の影響を受けます。trueにすると空間に固定されます。poseでz軸位置を1.0などと指定すれば、空中に浮きます。ぶつかっても動きません。


実行

いくつかの実行方法があります。


gazebo単体で起動

gazebo (worldファイル)とするとworldファイルを指定してgazeboを起動することができます。worldファイルのデバッグをするときなどに便利ですが、ROSと一緒に使うには不向きです。


worldを指定してgazeboを起動

roscd sim3_lecture/worlds/

gazebo world_test1.world

sim3_world1.png

ちなみにこの方法で起動すると、ターミナルでCtrl+Cをしてgazeboを落とそうとすると時間がかかります。GUIの×ボタンを押しましょう。


ROSのlaunchから実行(フルパスで指定)

gazebo_rosパッケージにあるempty_world.launchのargのworld_nameでworldファイル名を指定します。しかしこれはフルパスまたはGAZEBO_RESOURCE_PATHに通っているworldファイルしか読み込んでくれません。


worldを指定してgazeboを起動

roscd sim3_lecture/worlds/

roslaunch gazebo_ros empty_world.launch world_name:=`pwd`/world_test1.world


ROSのlaunchから実行(環境変数でパスを通す)


worldを指定してgazeboを起動

roscd sim3_lecture/worlds/

export GAZEBO_RESOURCE_PATH=$GAZEBO_RESOURCE_PATH:`pwd`
roslaunch gazebo_ros empty_world.launch world_name:=world_test1.world


ROSのlaunchから実行(package.xmlでパスを通す)

ROSを使うならこの方法が一番です。


sim3_lecture/package.xmlに追加

  <exec_depend>gazebo_ros</exec_depend>

<export>
<gazebo_ros gazebo_media_path="${prefix}/worlds" />
</export>
</package>


ファイルを編集したら以下を実行します。設定の読み込みのための再起動などは必要ありません。


worldを指定してgazeboを起動

roslaunch gazebo_ros empty_world.launch world_name:=world_test1.world 



coke缶が出てこないときは

coke_canがローカルに保存されている(~/.gazebo/models以下にcoke_canというディレクトリがある)場合でないと表示されません。

無いなら一度gazeboを開いてInsertタブ開いてその中から「Coke Can」を選んで配置してみてください。


参考

環境を作ろう

Gazebo + ROS で自分だけのロボットをつくる

Gazeboによるマニピュレータのシミュレーション


目次ページへのリンク

ROS講座の目次へのリンク