Updated on: 2018-02-27
本セクションではURDFの基本を説明し、簡単な移動型ロボットのURDFの作成によってURDFの作成方法を学習します。
作成する移動型ロボットは下記のRT製「Raspberry Pi Mouse」に類似です。 説明のためキャスターを追加します。
下記はURDFファイルの簡単な例です。 ファイルの内容がレーベルされています。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
<robot name="simple_urdf_sample"> <!-- ロボット定義の要素 -->
<material name="grey"> <!-- 色やテクスチャ -->
<color rgba="0.2 0.2 0.2 1"/>
</material>
<link name="link_1"> <!-- ロボットの一つの部分 -->
<visual> <!-- その部分の表示 -->
<geometry>
<box size="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision> <!-- その部分の衝突データ -->
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
<inertial> <!-- その部分の慣性データ -->
<mass value="1.0"/>
<intertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.1" ixz="0.1"/>
</inertial>
</link>
</link name="link_2> <!-- ロボットのもう一つの部分 -->
<visual>
<geometry>
<mesh filename="mesh.stl"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.5 0.5 0.5"/>
</geometry>
</collision>
</link>
<joint name="joint_1" type="revolute"> <!-- ロボットの部分のつなぎ方 -->
<origin xyz="1 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<parent link="link_1"/>
<child link="link_2/>
</joint>
</robot>
下記で要素を簡単に説明します。詳細はURDFのドキュメントに参照してください。
<robot>
name
はそのロボットの名前(基本的種類)を指定します。
すべてのURDFの要素は<robot>
の中に置きます。<material>
rviz
等でURDFを表示するときに利用されます。
ロボットの色等を定義します。
material
を定義するときに、中に色等を指定します。
すでに別の所で定義されたmaterial
なら、利用する時に中身はなくても問題ありません。
<visual>
でこれがなかったら、そのlink
は薄い灰色で表示されます。<link>
link
の組み合わせとして定義します。<visual>
<link>
の中にそのリンクの表示方法を定義します。
中身は主に3次元データ(部分のモデル)の定義及び表示するときに利用する色かテクスチャです。<collision>
<link>
の中にそのリンクの衝突データを定義します。
3次元データとして定義します。<inertial>
<link>
の中にそのリンクの物理的なデータを定義します。
おもにシミュレーションのために利用されます。
詳細は次のセクションに参照してください。<joint>
<robot>
の中に利用します。
リンクとリンクをつなげるジョイントを定義します。リンク、ジョイント等の順番は自由にできます。
URDFでロボットを定義することは基本的に下記の順番で行います。
ロボットの部分を決めます。
部分は必ず他のロボットの他の部分に対して動くことが必要ではありません。 作成便利さ等の場面でもロボットを部分に分けることもできます。 例えば移動型ロボットのシャーシとその上に固定されているフレームとフレームに固定されている画面は一つの部分としてまとめることも、別々の部分にすることも可能です。
部分づつにリンクを定義します。 リンクに表示用の3次元データを入れます。 必要におおじて衝突データや物理的なデータを入力します。 表示用のデータはデバッグに利用するので今入れる方がいいですが、衝突などのデータは後に入れても問題ありません。
リンクをつなげるジョイントを定義します。 リンクに対しての位置及び動きかた(動くジョイントのみ)を定義します。
シミュレーションにも利用する場合に、シミュレータ用のデータを定義します。 ジョイントのアクチュエータやコントローラ、センサーにスペックなどを入力します。 詳細は次のセクションに参照してください。
これから移動型ロボットを定義します。 定義するロボットは下記の図で簡単に示します。
ロボットを5つのリンクに分けました。
ロボットの定義の始まりとして、シャーシのリンクを定義します。
まずは新しいワークスペースとパッケージを作成し、空のURDFファイルを作成します。 端末で下記を実行してください。
1
2
3
4
5
6
7
8
9
10
11
12
13
$ cd ~/
$ mkdir -p ~/urdf_ws/src/
$ cd ~/urdf_ws/src/
$ catkin_init_workspace
Creating symlink "/home/username/urdf_ws/src/CMakeLists.txt" pointing to
"/opt/ros/kinetic/share/catkin/cmake/toplevel.cmake"
$ catkin_create_pkg --rosdistro kinetic mobile_robot_description
Created file mobile_robot_description/package.xml
Created file mobile_robot_description/CMakeLists.txt
Successfully created files in /home/username/urdf_ws/src/mobile_robot_description. Please adjust the values in package.xml.
$ cd mobile_robot_description/
$ mkdir urdf
$ touch urdf/mobile_robot.urdf
~/urdf_ws/src/mobile_robot_description/urdf/mobile_robot.urdf
をお好みのエディタで開いて、下記の内容を入力します。
1
2
3
<?xml version="1.0" ?>
<robot name="mobilerobot">
</robot>
URDFでは、ロボットはlink
の組み合わせとして定義します。
一つのリンクはロボットの一つの部分を定義します。
rviz等の可視化で表示方法、制御アルゴリズム用の衝突情報及びシミュレータようの物理的なデータをこの要素に入力します。
リンクはツリーのような構造に組み合わせます。 ロボットにほとんど利用されないループの構造はURDFでは不可能です。 (GazeboのSDFフォーマットで利用可能です。)
リンクの中身はは下記のように関連します。
すべてのデータは原点を持ちます。
この原点はそのデータの位置を決めます。
例えば、visual
の表示ようの3次元データはvisual
要素の中に指定する原点に対して表示されます。
visual
、collision
及びinertial
の原点は リンクの原点や親ジョイントに対してリンクの動き方に影響ありません。
3次元データのどこから書かれたことだけに影響あります。
親ジョイントに対してリンクの動き方(例えばどの点を回るか)を決めることは親ジョイントの原点だけです。
すなわち親ジョイントの原点はリンクの原点になります。
そのリンクに繋げられている物の位置はこの原点に対して指定します。
リンクの名前は自由に決められます。
ただ、ROS ではリンクツリーのルートとなるリンクはbase_link
と呼ぶことが基本です。
移動型ロボットの場合はこのbase_link
はシャーシです。
地図上のロボットの位置を指定する点になります。
マニピュレータの場合はbase_link
はマニピュレータの固定される部分です。
URDFでは空のリンクも可能ので、base_link
をシャーシにすることの代わりに空のリンクを作成し、それをbase_link
と呼び、シャーシをその空のリンクの子にすることも可能です。
mobile_robot.urdf
にシャーシのリンクを追加します。
表示用の3次元データも定義します。
1
2
3
4
5
6
7
8
9
10
11
<robot name="mobilerobot">
<!---- ここから追加 ---->
<link name="base_link">
<visual>
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
</visual>
</link>
<!---- ここまで追加 ---->
</robot>
URDFでジオメトリを指定する方法は2つあります。
box
(箱)
3サイドの長さをx y z
の順番で指定します。
cylinder
(円筒)
長さと半径を指定します。
sphere
(玉)
半径を指定します。
.stl
ファイルとColladaの.dae
ファイルが利用可能です。シャーシをbox
として定義しました。
原点は指定しなかったので、ディフォルトのbox
の中心になります。
リンクに複数のvisual
要素の利用は可能です。
複雑な形や複数のポリゴンメッシュ(それともプリミティブとポリゴンメッシュの組み合わせ)の時に複数のvisual
要素で指定できます。
下記の追加でRaspberry Pi Mouseの上に付いている部品をシャーシのリンクに追加します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
<robot name="mobilerobot">
<link name="base_link">
<visual>
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
</visual>
<!---- ここから追加 ---->
<visual name="regulators">
<geometry>
<box size="0.005 0.065 0.02"/>
</geometry>
<origin xyz="0.04 0 0.036" rpy="0 0 0"/>
</visual>
<visual name="connector">
<geometry>
<box size="0.075 0.016 0.026"/>
</geometry>
<origin xyz="0 -0.027 0.039" rpy="0 0 0"/>
</visual>
<!---- ここまで追加 ---->
</link>
</robot>
今回はvisual
要素毎に原点を指定しました。
リンクの親ジョイントが内ので、リンクの原点はリンクの中心になります。
なので上に載せたい部品はこの点に対して原点を指定します。
名前も指定しました。
visual
要素に名前は必須ではありませんが、複雑な形であれば名前を付けるとメンテナンスがより楽になります。
これで簡単なURDFがあります。
URDFファイルに問題があるか確認します。
check_urdf
というツールでエラーを探します。
1
2
3
4
5
$ cd ~/urdf_ws/src/mobile_robot_description/urdf/
$ check_urdf mobile_robot.urdf
robot name is: mobilerobot
---------- Successfully Parsed XML ---------------
root Link: base_link has 0 child(ren)
URDFを確認とデバッグするためにurdf_tutorial
パッケージにURDF表示するlaunch
ファイルを利用します。
1
2
$ cd ~/urdf_ws/src/mobile_robot_description/urdf/
$ roslaunch urdf_tutorial display.launch model:=mobile_robot.urdf gui:=False
rviz
が起動しロボットのシャーシを表示します。
rviz
の閉じるかおとまたは端末で__Ctrl+c__{: style=”border: 1px solid black” } で終了します。
リンクに衝突データを追加します。
ただの可視化用のURDFであれば衝突データが必要ではありませんが、指定しないとナビゲーションの制御アルゴリズムの利用することやGazebo上でシミュレーションすることは不可能です。 表示用のデータのそっくりにしても、ある方がいいです。
衝突チェックのアルゴリズムは、より簡単な3次元データであればより早く衝突の確認ができます。
とくにナビゲーションやMoveIt!の制御アルゴリズムに利用されるので、できるだけ簡単にします。
<visual>
が複雑であれば<collision>
の定義が大事です。
mesh
の利用よりプリミティブ(box
等)の利用で更に早いアルゴリズムの利用が可能になります。
mesh
を利用する場合は、1000フェース以下がおすすめです。
リンク毎に衝突データを定義します。
collision
要素はvisual
要素と似ています。
フォーマットは同じで、利用可能なジオメトリも同じです。
下記のようにmobile_robot.urdf
にシャーシの衝突ジオメトリを追加します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
<robot name="mobilerobot">
<link name="base_link">
<visual>
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
</visual>
<visual name="regulators">
<geometry>
<box size="0.005 0.065 0.02"/>
</geometry>
<origin xyz="0.04 0 0.036" rpy="0 0 0"/>
</visual>
<visual name="connector">
<geometry>
<box size="0.075 0.016 0.026"/>
</geometry>
<origin xyz="0 -0.027 0.039" rpy="0 0 0"/>
</visual>
<!---- ここから追加 ---->
<collision>
<geometry>
<box size="0.13 0.1 0.078"/>
</geometry>
<origin xyz="0 0 0.013" rpy="0 0 0"/>
</collision>
<!---- ここまで追加 ---->
</link>
</robot>
衝突データを簡単にするために、ロボットのシャーシを全体的に囲むbox
にしました。
box
の高さはシャーシのbox
の高さより大きいので中心(すなわちbox
の原点)をリンクの原点より少し高く置くことも必要です。
もう一度rviz
で確認します。
rviz
で衝突データの表示を選択するとシャーシのリンクの回りにbox
が表示されます。
Alpha
を少し半透明にすると見やすくなります。
1
2
$ cd ~/urdf_ws/src/mobile_robot_description/urdf/
$ roslaunch urdf_tutorial display.launch model:=mobile_robot.urdf gui:=False
シャーシのリンクに色を指定しなかったので、表示されるときにディフォルトの色が利用されます。 もしロボットは赤でよければそのままでいいですが、全部が赤であることはつまらないので、ここで違う色を指定します。
URDFでは色とテクスチャはmaterial
要素で指定します。
material
要素の使い方は2つあります。
マテリアルを定義するためにmaterial
要素を利用します。
material
要素の中身で色かテクスチャを指定します。
URDFの別の所で名前を利用するとこのマテリアルに参照できます。
マテリアルを利用するためにmaterial
要素を利用します。
別の所で定義したマテリアルの名前を利用して、そのマテリアルに参照してここにも利用することです。
マテリアルはvisual
の中で利用する所で定義することが可能ですが、メンテナンス性と再利用性の向上のためにlink
要素の外で定義して、visual
の中で参照することだけがおすすめです。
下記でmobile_robot.urdf
のトップに2つのマテリアルの定義を追加します。
1
2
3
4
5
6
7
8
9
10
<robot name="mobilerobot">
<!---- ここから追加 ---->
<material name="black">
<color rgba="0.2 0.2 0.2 1"/>
</material>
<material name="grey">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<!---- ここまで追加 ---->
<link name="base_link">
そしてリンクのvisual
要素でマテリアルを利用します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
<link name="base_link">
<visual>
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
<!---- ここから追加 ---->
<material name="grey"/>
<!---- ここまで追加 ---->
</visual>
<visual name="regulators">
<geometry>
<box size="0.005 0.065 0.02"/>
</geometry>
<origin xyz="0.04 0 0.036" rpy="0 0 0"/>
<!---- ここから追加 ---->
<material name="black"/>
<!---- ここまで追加 ---->
</visual>
<visual name="connector">
<geometry>
<box size="0.075 0.016 0.026"/>
</geometry>
<origin xyz="0 -0.027 0.039" rpy="0 0 0"/>
<!---- ここから追加 ---->
<material name="black"/>
<!---- ここまで追加 ---->
</visual>
もう一度rviz
で確認します。
1
2
$ cd ~/urdf_ws/src/mobile_robot_description/urdf/
$ roslaunch urdf_tutorial display.launch model:=mobile_robot.urdf gui:=False
ロボットのシャーシができたので、それにつながっている部分を別のリンクとして定義して、ジョイントで繋げます。 まずはロボットの後ろにあるキャスターを定義します。
上記に表示されているロボットの概要の図で見えるように、キャスターは2つのリンクで定義します。 一つはキャスターの車輪です。もう一つはその車輪とシャーシをつなげるサポートです。 別々で動くので別々のリンクとして定義します。
サポートのリンクはbox
として定義します。
下記をmobile_robot.urdf
の下(robot
要素の中)に追加します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
<collision>
<geometry>
<box size="0.13 0.1 0.078"/>
</geometry>
<origin xyz="0 0 0.013" rpy="0 0 0"/>
</collision>
</link>
<!---- ここから追加 ---->
<link name="caster_support">
<visual>
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
<material name="grey"/>
</visual>
<collision>
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
</collision>
</link>
<!---- ここまで追加 ---->
</robot>
box
の原点をディフォルトの中心から移動しました。
こうした理由は、リンクをジョイントにつなげるときにbox
の回転の中心をフェースに置きたいです。
そのままにしたら回転の中心はbox
の真ん中になります。
シミュレーションなどに影響ありませんが、可視化するときに格好的にこの方がいいです。
この時点でrviz
で確認しようとしたら、下記のようなエラーが出ます。
1
[ERROR] [1519973578.904519815]: Failed to find root link: Two root links found: [base_link] and [caster_support]
上記のエラーの原因はURDFに2つのリンクがあるけどそのリンクのつながり(ジョイント)は定義されていません。 URDFでリンクは必ずツリーの構造にすることが必要です。 親リンクがないリンクはツリーのルートになるが、親リンクがないリンクは一つではないとどちらがツリーのルートか判断できないので処理が失敗します。
次に、シャーシのリンクとキャスターサポートのリンクをつなげるジョイントを定義します。
URDFではロボットはリンクの組み合わせです。 ジョイントはそのリンクの組み合わせ方法を定義します。 すなわちリンクと他リンクの関連です。
移動可能なジョイントであれば、可能な動き方とその動きの中心(舳)を指定します。 そしてジョイントは親リンクと子供リンクを持ちます。 下記の図のように親リンクの原点に対して、子供リンクの原点をどこに置くかを指定します。
下記は利用可能なジョイントの種類です。
fixed
continuous
revolute
prismatic
floating
planar
下記をmobile_robot.urdf
に追加して、base_link
とcaster_support
を繋げます。
1
2
3
4
5
6
7
8
9
10
11
</link>
<!---- ここから追加 ---->
<joint name="caster_support_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="caster_support"/>
<origin xyz="-0.065 0 -0.01" rpy="0 0 0"/>
</joint>
<!---- ここまで追加 ---->
</robot>
下記、joint
要素の内容を説明します。
<joint name="caster_support_joint" type="continuous">
ジョイントの種類はcontinous
です。
このキャスターは永遠に回転できます。
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="caster_support"/>
<origin xyz="-0.065 0 -0.01" rpy="0 0 0"/>
rviz
でジョイントとキャスターのサポートのリンクを確認します。
1
2
$ cd ~/urdf_ws/src/mobile_robot_description/urdf/
$ roslaunch urdf_tutorial display.launch model:=mobile_robot.urdf gui:=False
キャスタサポートとシャーシのタスクフレームは表示されます。 そしてつながっている黄色い線はタスクフレームの関係を示します。 今タスクフレームは2つしかありませんが、タスクフレームが多くなるとこの黄色い線が大事になります。
もう一度rviz
を起動して、そして今回はgui
引数をTrue
にします。
1
$ roslaunch urdf_tutorial display.launch model:=mobile_robot.urdf gui:=True
下記のようなUIが表示されます。
スライダーをいじるとrviz
上でキャスターサポートが回転します。
動かすとリンクとジョイントのそれぞれの原点の関係が明確になります。
こう動かせることは、制御UIは/joint_states
トピックにジョイントの位置をパブリッシュしているからです。
詳細はロボットの可視化に参照してください。
キャスターサポートに車輪を追加します。
mobile_robot.urdf
に下記のリンクとジョイントを追加します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
</joint>
<!---- ここから追加 ---->
<link name="caster_wheel">
<visual>
<geometry>
<cylinder length="0.005" radius="0.02"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.02"/>
</geometry>
</collision>
</link>
<joint name="caster_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="caster_support"/>
<child link="caster_wheel"/>
<origin xyz="-0.02 0 -0.02" rpy="-1.5708 0 0"/>
</joint>
<!---- ここまで追加 ---->
</robot>
車輪に円筒のプリミティブを利用しています。
円筒はディフォルトとしてX舳に合わされるので、車輪が正しい方向になるためにリンクを回転することが必要です。
visual
、collision
及びinertial
の中でそれぞれの原点(3箇所)を回転することでするか、ジョイントの原点(1箇所)を回転することでするか選択できます。
1箇所でする方が楽ですが、子供リンクの先にされにリンクを付けるつもりであれば、ジョイントの回転のおかげでリンクづつの座標系がわかりにくくなることがあります。
今回は車輪で子供リンクの先に何も付けるつもりはないので、ジョイントの原点を回転する方法を選択しました。
マニピュレータの場合はジョイントよりvisual
等の原点を回転する方がいいケースは多いです。
rviz
で見ると下記のようにキャスターの車輪が追加されました。
最後にロボットのドライブウィールとなる2個の車輪を追加します。
キャスタの車輪と同じように追加します。
下記をmobile_robot.urdf
に追加します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
</joint>
<!---- ここから追加 ---->
<link name="right_wheel">
<visual>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
</collision>
</link>
<joint name="right_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 0.054 -0.021" rpy="-1.5708 0 0"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
</collision>
</link>
<joint name="left_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 -0.054 -0.021" rpy="-1.5708 0 0"/>
</joint>
<!---- ここまで追加 ---->
</robot>
最後に、固定されたジョイントを利用するためにロボットの上にレーザーセンサーを載せます。
mobile_robot.urdf
に下記の追加でレーザーセンサーの代表となるbox
をシャーシの上に載せます。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
</joint>
<!---- ここから追加 ---->
<link name="laser">
<visual>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="red">
<color rgba="0.9 0.1 0.1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
</link>
<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="laser"/>
<origin xyz="0 0 0.051" rpy="0 0 0"/>
</joint>
<!---- ここまで追加 ---->
</robot>
固定されたジョイントは動けないので回転軸等は要りません。
rviz
で完成したURDFが見えます。
下記は全体のURDFファイルです。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
<?xml version="1.0" ?>
<robot name="mobilerobot">
<material name="black">
<color rgba="0.2 0.2 0.2 1"/>
</material>
<material name="grey">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
<material name="grey"/>
</visual>
<visual name="regulators">
<geometry>
<box size="0.005 0.065 0.02"/>
</geometry>
<origin xyz="0.04 0 0.036" rpy="0 0 0"/>
<material name="black"/>
</visual>
<visual name="connector">
<geometry>
<box size="0.075 0.016 0.026"/>
</geometry>
<origin xyz="0 -0.027 0.039" rpy="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<box size="0.13 0.1 0.078"/>
</geometry>
<origin xyz="0 0 0.013" rpy="0 0 0"/>
</collision>
</link>
<link name="caster_support">
<visual>
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
<material name="grey"/>
</visual>
<collision>
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
</collision>
</link>
<joint name="caster_support_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="caster_support"/>
<origin xyz="-0.065 0 -0.01" rpy="0 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<cylinder length="0.005" radius="0.02"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.02"/>
</geometry>
</collision>
</link>
<joint name="caster_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="caster_support"/>
<child link="caster_wheel"/>
<origin xyz="-0.02 0 -0.02" rpy="-1.5708 0 0"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
</collision>
</link>
<joint name="right_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 0.054 -0.021" rpy="-1.5708 0 0"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.008" radius="0.024"/>
</geometry>
</collision>
</link>
<joint name="left_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 -0.054 -0.021" rpy="-1.5708 0 0"/>
</joint>
<link name="laser">
<visual>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="red">
<color rgba="0.9 0.1 0.1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
</link>
<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="laser"/>
<origin xyz="0 0 0.051" rpy="0 0 0"/>
</joint>
</robot>
このソースは以下のURLでダウンロード可能です。
下記のように自分のワークスペースに入れて利用できます。
1
2
3
4
5
6
$ cd ~/urdf_ws/src
$ git clone https://github.com/gbiggs/rosjp_urdf_tutorial_packages
$ cd rosjp_urdf_tutorial_packages
$ git checkout mobile_robot_primitives
$ cd ~/urdf_ws
$ catkin_make
上記のURDFはロボットを利用するために充分です。
しかし可視化として少し貧弱でしょう。
本物のロボットはbox
ではなかったら、可視化もbox
ではない方がいいでしょう。
そのために、リンクでプリミティブではなくてCADデータのようなポリゴンメッシュは利用できます。
visual
要素にもcollision
要素にもメッシュは利用可能です。
visual
に可視化をロボットとそっくりな格好にするために利用します。
collision
に複雑なロボットの形により近い形になる衝突データのために利用します。
ただし、衝突チェックはポリゴンメッシュが複雑になればなるほど処理の時間がかかるので、余計に細かい衝突データを作らない方がおすすめです。 ロボットが狭い所で活動してロボットの凹凸の部分が環境の凹凸の部分を回避することが必要ではなかったら、プリミティブまたは非常に簡単なポリゴンメッシュの利用がおすすめです。 そして、ポリゴンメッシュを利用する場合は、1000フェース以下がおすすめです。
これからポリゴンメッシュを利用して移動型ロボットの格好を少し改善します。
下記の実行で利用するポリゴンメッシュをダウンロードします。
1
2
3
4
5
$ cd ~/urdf_ws/src/mobile_robot_description/
$ mkdir meshes
$ cd meshes
$ wget https://github.com/gbiggs/rosjp_urdf_tutorial_packages/raw/master/mobile_robot_description/meshes/mobile_robot_caster.stl
$ wget https://github.com/gbiggs/rosjp_urdf_tutorial_packages/raw/master/mobile_robot_description/meshes/raspi_mouse_body.stl
次にmobile_data.urdf
で下記のように編集します。
visual
要素のジオメトリをプリミティブからポリゴンメッシュへ変更します。
collision
要素の内容は変更しません。
衝突チェックが早く行えるように簡単なデータのままにします。
まずはbase_link
のリンクを下記のように変更します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
<link name="base_link">
<visual>
<!---- ここから削除 ---->
<geometry>
<box size="0.13 0.1 0.052"/>
</geometry>
<material name="grey"/>
<!---- ここまで削除 ---->
<!---- ここから追加 ---->
<geometry>
<mesh filename="package://mobile_robot_description/meshes/raspi_mouse_body.stl"/>
</geometry>
<material name="grey"/>
<origin xyz="-0.041 -0.05 -0.02575" rpy="0 0 0"/>
<!---- ここまで追加 ---->
</visual>
<visual name="regulators">
<geometry>
<box size="0.005 0.065 0.02"/>
</geometry>
<origin xyz="0.04 0 0.036" rpy="0 0 0"/>
<material name="black"/>
</visual>
<visual name="connector">
<geometry>
<box size="0.075 0.016 0.026"/>
</geometry>
<origin xyz="0 -0.027 0.039" rpy="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<box size="0.13 0.1 0.078"/>
</geometry>
<origin xyz="0 0 0.013" rpy="0 0 0"/>
</collision>
</link>
ポリゴンメッシュを利用するvisual
要素に原点を追加しました。
ポリゴンメッシュの原点はbox
の中心と違くて、リンクの原点から離れているところです。
メッシュの表示位置が正しいようにメッシュの原点をリンクの原点から離れたところに置きます。
ポリゴンメッシュを作成するとき、メッシュの原点をリンクが固定される所に合わせるとURDFがより作成しやすくなります。
次にキャスターのリンクを下記のように変更します。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
<link name="caster_support">
<visual>
<!---- ここから削除 ---->
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
<!---- ここまで削除 ---->
<!---- ここから追加 ---->
<geometry>
<mesh filename="package://mobile_robot_description/meshes/mobile_robot_caster.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<!---- ここまで追加 ---->
<material name="grey"/>
</visual>
<collision>
<!---- ここから削除 ---->
<geometry>
<box size="0.02 0.02 0.04"/>
</geometry>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
<!---- ここまで削除 ---->
<!---- ここから追加 ---->
<geometry>
<box size="0.04 0.009 0.025"/>
</geometry>
<origin xyz="-0.015 0 0" rpy="0 0 0"/>
<!---- ここまで追加 ---->
</collision>
</link>
ポリゴンメッシュのファイル名はパッケージの中のパスとして指定しました。
このように指定すると、現在利用中のワークスペースにパッケージがあれば、またはバイナリからインストールしたパッケージであれば、rviz
等のツールはファイルが見つけられます。
パッケージとしてファイルパスを指定したので、今回rviz
で表示するためにまずはワークスペースをビルドすることが必要です。
下記の実行でurdf_ws
をビルドしてURDFファイルを表示します。
1
2
3
4
$ cd ~/urdf_ws
$ catkin_make
$ source devel/setup.bash
$ roslaunch urdf_tutorial display.launch model:=src/mobile_robot_description/urdf/mobile_robot.urdf gui:=True
rviz
でポリゴンメッシュのデータが利用されてより本物のロボットに近い可視化ができました。
衝突データの表示を入れると、衝突データは簡単だけどロボットを囲むようになっていると見えます。
このソースは以下のURLでダウンロード可能です。
下記のように自分のワークスペースに入れて利用できます。
1
2
3
4
5
6
$ cd ~/urdf_ws/src
$ git clone https://github.com/gbiggs/rosjp_urdf_tutorial_packages
$ cd rosjp_urdf_tutorial_packages
$ git checkout mobile_robot_meshes
$ cd ~/urdf_ws
$ catkin_make