🏙️

Gazebo: CADモデル、Actorを使用して自作worldを作成してみる

2023/03/22に公開

海洋ロボコンをやってた人です。

今回は、Gazeboで自作のworldファイルを作成してみたので、自身の備忘録かつ、本学の新4年生、在学生向けに記載していきます。

なぜまとめるかは以下です。

  • 簡単なworldファイルを3DCADやActor(人)モデルも交えて自作したかったため
  • Gazeboを使用したシミュレーションの理解を自分も深めたいため
  • 自分で後から見返すため(これ大事)

"もっとこうすれば簡単に使用できる" や "ここは違うのではないか"というご意見がありましたら、是非ご教授いただけますと幸いです。

なぐり書きの記事で恐縮ですが、本記事に対するコメントも積極的に募集しますので、ご不明点等ありましたら、よろしくお願いいたします。

Gazebo: CADモデル、Actorを使用して自作worldを作成してみる

環境は以下です。

実装したものは以下のようなものです。

https://twitter.com/tasada038/status/1638043526452903936

また、自作のworldファイルの要件定義として

  • 自作の街並みモデルをworldで使用すること
  • Actor(人)が速度を変えつつ歩行していること
  • ランダム配置したオブジェクトがあること(電柱をイメージ)

を想定して作成しています。

CADソフトで自作worldモデルをつくる

まずはCADソフトで自作のworldモデルを作成していきます。

自作のモデルを作るときは、Z軸UPとして作成してください。

上記では、X軸マイナス方向にモデルがあるので、あまり良くないスケッチの書き方です。
Gazebo内でスポーンするとき、XYZ原点(0,0,0)がデフォルトとなるので、CADソフトでスケッチするときも原点ベースで作成するのが好ましいです。

また単位は[mm]としていますが、Gazeboは[m]単位なのでスケッチ段階で単位を統一するか、stlファイル出力時に単位変換をする必要があります。

印刷オプション > 単位: メートル

と設定し.stlファイルとして出力できたら自作worldモデルの準備は完了です。

Gazebo用のパッケージを作成する

Gazebo用のパッケージですが、基本的なフォルダ構成はこちらと同じ形になっています。

https://zenn.dev/tasada038/articles/54f6111fb6e907

上記記事では、stlファイル出力をmm単位で行っているので、scaleを1/1000倍にしていますが、本記事ではメートル単位で出力しているので、model.sdfのscaleは1倍になっています。

modelsファイルの記述

modelsファイルでは、stlを呼び出すsdfファイルを記述のみを行い、このmodelsファイル自体を.worldファイルでインクルードするようにしていきます。

stlファイルをsdfで呼び出すには以下のように記述します。

パスはturtlebot3_gazebo/models/turtlebot3_jp_world_xxx/model.sdfです。

model.sdf
<?xml version='1.0'?>
<sdf version='1.6'>
    <model name="cityscape">
    <static>true</static>
    <link name="cityscapelink">
    
    <collision name="collision">
        <pose>7.5 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <uri>model://xxx/meshes/cityscape.stl</uri>
            <scale>1 1 1</scale>
          </mesh>
        </geometry>
        <max_contacts>10</max_contacts>
        <surface>
          <bounce/>
          <friction>
            <ode/>
          </friction>
          <contact>
            <ode/>
          </contact>
        </surface>
      </collision>

      <visual name="visual">
        <pose>7.5 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <uri>model://xxx/meshes/cityscape.stl</uri>
            <scale>1 1 1</scale>
          </mesh>
        </geometry>
        <material>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/FlatBlack</name>
          </script>
        </material>
      </visual>

    </link>
    </model>
</sdf>

また、Inventorで作成したCADモデルの位置をずらすときはposeタグでデフォルト位置を調整します(単位はメートル)

worldファイルの記述

先程定義した要件に従ってworldファイルに記述をしていきます。
パスはturtlebot3_gazebo/worlds/turtlebot3_jp_xxx.worldです。

  1. 自作のworldモデルをmodelよりインポート

model/モデル名
という形でインクルードするだけです。

xxx.world
    <!-- Load model -->
    <include>
      <uri>model://xxx</uri>
    </include>
  1. Actorモデルの利用

Actorモデルを使用するには以下のように記述します。

xxx.world
   <model name="actor0_collision_model">
      <pose>0 0 0 0 0 0</pose>
      <static>false</static>
      <link name="link">
        <collision name="link">
          <pose>0 -0.18 0.00 1.57 0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.3</radius>
              <length>1.8</length>
            </cylinder>
          </geometry>
        </collision>
      </link>
    </model>
    <actor name="actor0">
      <static>true</static>
      <skin>
        <filename>walk.dae</filename>
      </skin>
      <animation name="walking">
        <filename>walk.dae</filename>
        <interpolate_x>true</interpolate_x>
      </animation>
      <script>
        <ignore_obstacles>
          <model>ground_plane</model>
          <model>actor0_collision_model</model>
          <model>pillar</model>
        </ignore_obstacles>
        <trajectory id="0" type="walking">
          <waypoint>
            <time>0</time>
            <pose>6 1.1 0 0 0 3.14</pose>
          </waypoint>
          <waypoint>
            <time>25</time>
            <pose>-9 1.1 0 0 0 3.14</pose>
          </waypoint>
          <waypoint>
            <time>27.5</time>
            <pose>-9 6.5 0 0 0 0</pose>
          </waypoint>
          <waypoint>
            <time>30</time>
            <pose>9.5 6.5 0 0 0 0</pose>
          </waypoint>
          <waypoint>
            <time>32.5</time>
            <pose>9.5 1.1 0 0 0 -3.14</pose>
          </waypoint>
          <waypoint>
            <time>37.5</time>
            <pose>6 1.1 0 0 0 -3.14</pose>
          </waypoint>
        </trajectory>
      </script>
    </actor>

waypointでは、AというwaypointからBというwaypointへ移動する際の時間および位置を指定します。

例えば、

xxx.world
          <waypoint>
            <time>32.5</time>
            <pose>9.5 1.1 0 0 0 -3.14</pose>
          </waypoint>
          <waypoint>
            <time>37.5</time>
            <pose>6 1.1 0 0 0 -3.14</pose>
          </waypoint>

の部分は位置(x, y, z) = (9.5, 1.1, 0)から(x, y, z) = (6, 1.1, 0)の移動に37.5s - 32.5s = 5s使って移動することを意味します。

したがって、Actorの速度で表すと、3.5m / 5s = 0.7m/sと求めることができます。

この書き方はプログラムとしては綺麗ではないですが、Actorの速度を簡単に変更できます。


また、scriptタグ内のignore_obstacleタグはロボットが障害物と衝突することを防ぐために使用され、ignore_obstacleタグに指定した障害物は、衝突せずに通過することができます。

こちらを設定すると衝突せずにオブジェクトの中を通過するので、シミュレーションとしては如何なものかという点があると思います。

  1. populationによりオブジェクトをランダム複数配置

最後に電柱などのオブジェクトをランダム位置に複数個配置して見たいと思います。

ランダム複数配置にはPopulation of modelsというタグを使用します。

xxx.world
    <population name="pillar_population_1">
      <model name="pillar_1">
        <link name='obstacle_1'>
          <collision name='obstacle_1'>
            <geometry>
              <cylinder>
                <radius>0.2</radius>
                <length>3</length>
              </cylinder>
            </geometry>
            <max_contacts>10</max_contacts>
            <surface>
              <bounce/>
              <friction>
                <ode/>
              </friction>
              <contact>
                <ode/>
              </contact>
            </surface>
          </collision>

          <visual name='obstacle_1'>
            <geometry>
              <cylinder>
                <radius>0.25</radius>
                <length>3</length>
              </cylinder>
            </geometry>
            <material>
              <script>
                <uri>file://media/materials/scripts/gazebo.material</uri>
                <name>Gazebo/White</name>
              </script>
            </material>
          </visual>
        </link>
      </model>
      <pose>6 2 0 0 0 0</pose>
      <box>
        <size>6 0.4 0.01</size>
      </box>
      <model_count>2</model_count>
      <distribution>
        <type>random</type>
      </distribution>
    </population>

populationタグ直下にはオブジェクトのモデルを記述し、その直下に複数配置を行う原点と配置エリアを指定します。

xxx.world
      <pose>0 0 0 0 0 0</pose>
      <box>
        <size>2 2 0.01</size>
      </box>

上記では、poseタグがPopulationの中心位置で(0, 0, 0)、box_sizeがは中心位置からの配置エリアで2×2×0.01のボックス範囲で配置することを意味します。

model_countはその名のとおり、モデルの複製数、distributionタイプは配置の方法を設定できます。
randomとすれば、指定した配置エリアに対してランダムに配置され、linear-xなどとするとx軸上にランダム配置されます。

これで、ランダムに2つのcylinderが配置できるようになりました。

自作worldファイルを実行する

ROS 2 Humbleで実行するには、以下のようなlaunchファイルを作成します。

xxx.launch.py
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration


def generate_launch_description():
    launch_file_dir = os.path.join(get_package_share_directory('xxx'), 'launch')
    pkg_gazebo_ros = get_package_share_directory('gazebo_ros')
 
    world = os.path.join(
        get_package_share_directory('xxx'),
        'worlds',
        'xxx.world'
    )

    gzserver_cmd = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
        ),
        launch_arguments={'world': world}.items()
    )

    gzclient_cmd = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
        )
    )

    ld = LaunchDescription()

    # Add the commands to the launch description
    ld.add_action(gzserver_cmd)
    ld.add_action(gzclient_cmd)

    return ld

実行すると、CADで作成したモデルやActor、電柱のオブジェクトが表示されているのが分かります。

以上

Discussion