URDFでロボットモデルの作成

概要

 ROSのGazeboを使ったシミュレーションでは、ロボットのモデルデータをURDFで作成します。
 下記のページを参考に、Turtlebot3のような、差動2輪+補助輪型の移動ロボットのモデルを作成してみます。今回はモデルの作成がメインなので、センサーなどは付けず、手動操作でGazebo上を動くだけの移動ロボットとします。
 このページのパッケージのソースは、https://github.com/joe-ash/model01にアップしてあります。

基礎知識

URDF

 URDFは、Unified Robot Description Formatの略で、ロボットのモデル構造を記述するための書式です。URDFは、XML形式で、モデルの外観だけでなく、リンク構造や慣性などの動作も表すことができます。

 URDFでは、直方体、円柱、球、メッシュの4種類の基本形状の組み合わせで作成します。

基本形状タグ名
箱型(直方体)box
円柱cylinder
sphere
メッシュmesh

 URDFでは、座標系は右手系を使います。位置は、xyz(x座標、y座標、z座標)とrpy(ロール角、ピッチ角、ヨー角)で指定します。また、単位系はSI単位系を使います。

基本量基本単位
長さの単位m
角度の単位radian
質量の単位kg
力の単位N
慣性の単位kg・m2

URDFによるロボットモデル

 URDFによるロボットモデルは、robotタグの中の要素として作成していきます。
 URDFの構造はlinkをjointで繋ぎ合わせたツリー構造であり、1つのjointに対して親(parent)のlinkは1つしか指定できません。また、最上位のlinkがロボットの位置等の基準となります。
 linkタグは、ロボットの1つの部品を定義し、jointタグは、linkとlinkを繋げる部分を定義します。
 linkタグには、下記の属性と要素などが定義できます。

属性・要素名内容
nameリンクの名前
origin位置(xyz, rpy)
visual外観に関するデータ
collision衝突に関するデータ
inertial慣性に関するデータ

 jointタグには、下記の要素などが定義できます。

属性・要素名内容
nameジョイントの名前
type形式
fixed 固定
continuous 軸方向に回転
revolute 上限、下限の範囲で、軸方向に回転
prismatic 軸方向にスライド
floating 球面ジョイント、6自由度を持つジョイント
parent親リンク
child子リンク
origin親リンクと子リンクの位置関係
axis回転軸、スライド軸
limitジョイントの可動範囲

 linkはvisual(外観)、collision(衝突)、inertial(慣性)の3つの要素で構成されますが、visualはgazeboやrvizでの表示に必要なだけで実機の制御には使われません。linkやjointをgazeboで正しくシミュレーションするためには、<gazebo reference="[link・joint名]">で各パラメータを設定する必要があります。
 gazeboタグには、下記の要素などが定義できます。

要素名内容
material外観表示に使われる物質
turnGravityOff重力の使用
dampingFactorリンク速度の減衰係数
maxVel最大速度
mu1接地摩擦係数μ1
mu2接地摩擦係数μ2
fdir1進行方向
kp剛体面の接触剛性k_p
kd剛体面の摩擦減衰k_d

Xacro

 Xacroは、XML macroの略で、テンプレートとなるXML(URDF)に対して、属性やプロパティの上書き、追加をしながら使いまわすことができます。URDFだけで記述すると、同じ部品を使った場合などの繰り返しパターンもすべて記述する必要があるため、タイヤの様な同じ形状の部品を複数取り付ける場合には、Xacroを利用すると便利です。
 基本的な書式は、

<xacro:XXXXX params="p1 p2 p3">~</xacro:XXXXX>
 または
<xacro:macro name="XXXXX" params="p1 p2 p3">~</xacro:macro>
 でマクロを定義し、
<XXXXX a="***" b="***" c="***" />
 と書けば、マクロで定義したタグの中身に、paramsで指定した引数を変数として反映させた内容へと置換されます。
 また、launchのurdfの指定で
command="$(find xacro)/xacro ****.xacro"
 の様に書いて、その都度展開させるような書き方もできます。

作成するロボットの仕様

 作成するロボットは、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   補助輪

ロボットの作成

ビルド環境の作成

 URDFのビルド用の環境を作成します。

$ cd ~/catkin_ws/src
$ catkin_create_pkg model01 urdf xacro
$ cd model01
$ mkdir urdf
$ mkdir launch

ファイル構成

 環境ができたら、urdfフォルダとlaunchフォルダに各ファイルを設置します。

model01/urdf/model01.urdf.xacroロボットモデルのXacroファイル
model01/urdf/common.urdf.xacro共通処理のXacroファイル
model01/urdf/wheel.urdf.xacroホイールのXacroファイル
model01/urdf/caster.urdf.xacroキャスターのXacroファイル
model01/launch/model01.launchロボット表示用のlaunchファイル

model01.urdf.xacroの説明

 model01.urdf.xacroファイルは、ロボットモデルのXacroファイルです。下記の記述で、common.urdf.xacro、wheel.urdf.xacro、caster.urdf.xacroの3つのヘッダファイルを利用しています。ヘッダファイルのsubというパラメータは、XacroがURDFに展開した時にユニークな名前にするためのサブIDです。左右であればlrの文字を指定しても構いませんし、0,1,2,3のような連番を付加しても構いません。

  <!-- Included URDF/XACRO Files -->
  <xacro:include filename="$(find model01)/urdf/common.urdf.xacro" />
  <xacro:include filename="$(find model01)/urdf/wheel.urdf.xacro" />
  <xacro:include filename="$(find model01)/urdf/caster.urdf.xacro" />

 リンクには、ロボットの基準位置となる原点を表すリンクがあります。一般的には、base_linkと言う名前で定義されることが多いですが、差動2輪型の移動ロボットの場合、駆動輪の中心の地上部分を基準にすることが多いので、base_footprintと言う名前で作成しています。
 ロボットのデータは、x軸方向に進行するように、linkデータとjointデータの設定を行っています。

  <!-- base_footprint Definition -->
  <link name="base_footprint" />

 ロボットの各部品は、linkタグによって定義します。
 visualタグで、大きさや色などの物理的なデータを定義します。色は、common.urdf.xacroを参照するようにしているため、materialタグにWhiteと色名で設定してあります。gazeboは、visualの色を参照しないので、gazeboで使う色はvisualタグとは別のgazeboタグにも、Gazebo/Whiteと定義する必要があります。
 inertiaタグの値は、要素の形によって決まるため、Xacroのマクロを使って計算しています。

  <link name="base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <visual>
      <geometry>
        <box size="0.069 0.138 0.050"/>
      </geometry>
      <material name="White" />
    </visual>
    <inertial>
      <mass value="0.2" />
      <origin xyz="0 0 0" rpy="0 0 0" />
      <xacro:box_inertia m="0.2" x="0.069" y="0.138" z="0.050" />
    </inertial>
  </link>

  <gazebo reference="base_link">
    <material>Gazebo/White</material>
    <turnGravityOff>false</turnGravityOff>
  </gazebo>

 各リンクには、上位リンクとの位置関係と関節などの接続関係を表すジョイントが必要ですので、jointタグによって定義します。

  <joint name="base_joint" type="fixed">
    <origin xyz="0 0 0.045" rpy="0 0 0" />
    <parent link="base_footprint" />
    <child  link="base_link" />
  </joint>

 一番下のdifferential_drive_controllerの設定は、差動2輪型のロボットの動作を定義するための設定です。ロボットやモーターを購入すると、その機種に合ったパラメータが提供されていると思いますので、ここでは説明を省略します。Model01は、大きさと重さはTurtlebot3 Burgerに合わせていますので、Turtlebot3 Burgerの設定を参考にして設定しています。変更する場合は、上記リンクにあるGazeboプラグインの説明を参照してください。

model01/urdf/common.urdf.xacroの説明

 common.urdf.xacroファイルは、各種ロボットで共通に利用可能な、定数の設定や、慣性の計算や、色の指定などを行います。慣性の計算は、箱型、円柱型、球型の物体に対して、大きさなどの引数を渡すことで計算できます。色の指定はrgbaでなく、色名で指定可能になるため、xacroのソースファイルが見やすくなるのと、複数の部品の色を同時に変えることができるようになります。

model01/urdf/wheel.urdf.xacroの説明

 wheel.urdf.xacroファイルは、駆動輪のホイールの定義を行います。通常、右と左で同じ車輪を使うことが多いので、定義が半分になるだけでなく、同じホイールを使う他のロボットとも共通に利用することもできます。
 車輪はURDFのcylinder要素として作成します。cylinder要素はz軸の回転体として作成されるため、x軸方向に進むようにx軸のロール角を90度(π/2radian)回転します。

model01/urdf/caster.urdf.xacroの説明

 caster.urdf.xacroファイルは、補助輪用のキャスターの定義を行います。補助輪は、Gazeboの動作上あまり重要でないため、球形にしてあります。2軸キャスターであれば、2個の円柱をジョイントで繋ぐべきだと思います。

model01/launch/model01.launchの説明

 model01.launchファイルは、Gazebo内にロボットモデルを表示します。  Gazeboの起動は、gazebo_rosパッケージに含まれるempty_world.launchを利用しています。empty_world.launchは、word_nameという引数で、Worldファイルを切り替えることができます。
 robot_descriptionでは、Xacroを使って、urdfファイルを再生成しています。そのため、起動には時間がかかりますが、常に最新のデータを参照されるようにしています。
 最後に、urdf_spawnerによって、モデルをgazeboに登録しています。

<launch>
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" default="worlds/empty.world"/>
  </include>

  <param name="robot_description"
    command="$(find xacro)/xacro $(find model01)/urdf/model01.urdf.xacro"/>

  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
    args="-urdf -model model01 -param robot_description"/> 
</launch>

URDFの作成、確認

 以下のコマンドでXacroを起動し、URDFを作成し確認します。
 Kineticの場合は、--inorderオプションを追加しないとワーニングエラーになります。Xacroの文法は、よく変更があるため、バージョンが異なるとエラーになる可能性があります。

$ cd ~/catkin_ws/src/model01/urdf
$ rosrun xacro xacro --check-order model01.urdf.xacro
$ rosrun xacro xacro model01.urdf.xacro > model01.urdf
$ check_urdf model01.urdf

 実行すると、model01.urdfというURDFファイルができます。ファイルを見ると、Xacroによって、インクルードファイルの内容が展開されているのが分かります。

ロボットの表示

Gazeboで表示

 Gazeboを起動し、作成したロボットを表示します。

$ roslaunch model01 model01.launch

 下記のような画面が表示されます。
 

キーボードでロボットを操作

 gazeboのプラグインに/cmd_velにTwistメッセージを送ればロボットを操作できる仕様になっています。
 別端末を開き、teleop_twist_keyboardを起動すると、作成したロボットを操作することができます。

$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py

 キー操作の方法は端末上に表示されますので、説明に従って操作してください。

Worldファイルの設定

ファイル構成

 背景が何もないと殺風景なので、Gazeboに入っているWorldデータに、表示してみます。

Gazeboで表示

 launchファイルを使ってGazeboを起動し、作成したロボットを表示します。
 ネット上にあるモデルデータをダウンロードしますので、最初に表示するときは数分間かかります。

$ roslaunch model01 model01_cafe.launch

 下記のような画面が表示されます。
 
 別端末を開き、teleop_twist_keyboardを起動すれば、ロボットを動かすこともできますが、カフェのカウンター内に入ろうとすると、段差によって転倒するため動けなくなってしまいます。


Copyright (C) ASH Joe Masumura