xacroでロボットを書く[1] - jointとlink
GAZEBOでロボットをシミュレーションさせるには、ロボットの形とか質量とか色々定義する必要がある。 以前URDF(Unified Robot Description Format)で三輪車みたいな対向二輪型ロボットを書いたけど、めちゃくちゃ長くて人間が書くものじゃない。 今回マクロを使ってURDFが書けるxacro(XML macro)を使ってみたのでメモ。最後に参考にしたサイトをペタペタ貼ってるので、そっちを見たほうが理解が深まるはず。
動作環境
- Ubuntu16.04
- ROS Kinetic Kame
- GAZEBO 7.0.0
練習の記録
今回やってることはこちらのリポジトリに公開してます。
作業用ディレクトリの作成
役割ごとに複数のパッケージに分けるのが主流らしい。
workspaceにそれらをまとめるディレクトリを作成する。
僕は最終的にナビゲーションをしてみたいので、今回はnavigation_practice
という名前にした。
$ cd ~/catkin_ws/src $ mkdir navigation_practice $ cd navigation_practice
Description packageの作成
xacroでロボットを定義するパッケージを作る。
大抵*_description
という名前が使われるらしい。
ロボットの名前が全然思いつかないので適当にmabot
と命名した。
これ見て作業をするなら適宜自分のロボットの名前に読み替えてください。
$ catkin_create_pkg mabot_description
部品を作る
今回作る対向二輪型ロボットは、body、wheel、casterで構成される。xacroは複数に分割して記述できるので、ロボットの部品ごとにファイルを分けて書くことにする。
まずは部品を入れておくディレクトリを作成。
$ mkdir mabot_description/urdf
追記: これからxacroやURDFを書いてはモデルが思ったとおりにできてるか確認することを繰り返すのだけど、VSCodeのプラグインを使うと書きながら常に確認しながら書けるのでおすすめ。使い方は下記記事に書いた。
部品の構成
部品はjoint
とlink
によって構成される。
- joint
joint
はlink
同士を結合させる要素。いくつか種類があって、単にlink
同士を固定するものや回転、スライドさせるものもある。
詳しくはこちら。 - link
部品の見た目や形、質量や慣性モーメントなどを設定する要素。
詳しくはこちら。
bodyの作成
まずはbodyを作る。 これにタイヤとかセンサーとかくっつける予定。 今回は単純に四角いモデルにしてみた。
$ mkdir mabot_description/urdf/body $ vim mabot_description/urdf/body/body.urdf.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:macro name="base" params="parent *joint_origin"> <joint name="base_joint" type="fixed"> <xacro:insert_block name="joint_origin"/> <parent link="${parent}"/> <child link="base_link"/> </joint> <link name="base_link"> <visual> <geometry> <box size="0.400 0.200 0.100"/> </geometry> </visual> <collision> <geometry> <box size="0.400 0.200 0.100"/> </geometry> </collision> <inertial> <origin xyz="0 0 0"/> <mass value="0.6"/> <inertia ixx="1e-3" ixy="0" ixz="0" iyy="1e-3" iyz="0" izz="1e-3"/> </inertial> </link> </xacro:macro> </robot>
wheel作成
次にwheelを作成する。今回は円柱で作成した。
$ mkdir mabot_description/urdf/wheel $ vim mabot_description/urdf/body/wheel.urdf.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:macro name="wheel" params="prefix parent *joint_origin *joint_axis"> <joint name="${prefix}_wheel_joint" type="continuous"> <xacro:insert_block name="joint_origin" /> <xacro:insert_block name="joint_axis" /> <parent link="${parent}" /> <child link="${prefix}_wheel" /> </joint> <link name="${prefix}_wheel"> <visual> <geometry> <cylinder radius="0.1" length="0.05"/> </geometry> </visual> <collision> <geometry> <cylinder radius="0.1" length="0.05"/> </geometry> </collision> <inertial> <origin xyz="0.0 0.0 0.0" /> <mass value="0.500"/> <inertia ixx="0.0013541667" ixy="0" ixz="0" iyy="0.0013541667" iyz="0" izz="0.0025"/> </inertial> </link> </xacro:macro> </robot>
caster作成
次にcasterを作成する。今回は球で作成した。
$ mkdir mabot_description/urdf/caster $ vim mabot_description/urdf/body/caster.urdf.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:macro name="caster" params="parent *joint_origin"> <joint name="$caster_joint" type="fixed"> <xacro:insert_block name="joint_origin" /> <parent link="${parent}" /> <child link="caster_link" /> </joint> <link name="caster_link"> <visual> <geometry> <sphere radius="0.05"/> </geometry> </visual> <collision> <geometry> <sphere radius="0.05"/> </geometry> </collision> <inertial> <origin xyz="0.0 0 0.0" /> <mass value="0.50" /> <inertia ixx="0.0025" ixy="0.0" iyy="0.0025" ixz="0.0" iyz="0.0" izz="0.0025" /> </inertial> </link> </xacro:macro> </robot>
部品を組み立てる
それぞれ別のxacroファイルに書いた部品を読み込み、配置を決めるxacroファイルを書く。
$ mkdir mabot_description/robots $ vim mabot_description/robots/mabot.urdf.xacro
<?xml version="1.0"?> <robot name="mabot" xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:include filename="$(find mabot_description)/urdf/body/body.urdf.xacro"/> <xacro:include filename="$(find mabot_description)/urdf/wheel/wheel.urdf.xacro"/> <xacro:include filename="$(find mabot_description)/urdf/caster/caster.urdf.xacro"/> <link name="base_footprint"/> <xacro:base parent="base_footprint"> <origin xyz="0 0 0"/> </xacro:base> <xacro:wheel prefix="right" parent="base_link"> <origin xyz="0.1 -0.17 0.0" rpy="1.57 0 0" /> <axis xyz="0 0 -1" /> </xacro:wheel> <xacro:wheel prefix="left" parent="base_link"> <origin xyz="0.1 0.17 0.0" rpy="-1.57 0 0" /> <axis xyz="0 0 1" /> </xacro:wheel> <xacro:caster parent="base_link"> <origin xyz="-0.15 0 -0.05"/> </xacro:caster> </robot>
rvizでモデルを確認する
2019/10/06 追記
VSCodeのExtensionsでURDFをプレビューできるものがあったので、あれこれ試すならこれが楽かも。
無事にxacroファイルを作ることができたか確認してみる。 作ったモデルの外観をrvizで表示するlaunchファイルを書く。 ついでにrvizの表示設定を保存するために、configディレクトリも作成しておく。
$ mkdir -p mabot_description/launch/config $ vim mabot_description/launch/display.launch
<launch> <!-- arguments --> <arg name="model" default="$(find mabot_description)/robots/mabot.urdf.xacro"/> <arg name="gui" default="True" /> <!-- prameters --> <param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)"/> <param name="use_gui" value="$(arg gui)"/> <!-- nodes --> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> <!-- rviz --> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find mabot_description)/launch/config/urdf.rviz" required="true" /> </launch>
作成したlaunchファイルを実行する。
$ roslaunch mabot_description display.launch
するとrvizが起動する。作成したロボットのモデルを表示するために、左下のAddボタンを押す。
表示する要素を選ぶ。今回はRobotModelを選択する。
FixedFrameをbese_footprintにする。
無事にロボットが表示されていることを確認する。
これをGAZEBO上で走らせるのはまた今度。
続き
動力と摩擦係数を設定して走らせる準備をした。
参考
- ロボット記述言語
- URDFの各要素について、図を用いて大変わかりやすく紹介されています
- xacro - ROS wiki
- xacroの各機能はこちらがわかりやすいです
- ROS講座68 xacroを使う1
- ROS講座73 xacroを使う2
- xacroの機能に関してサンプルコードを交えて解説されています
- 移動型ロボットのシミュレーション
- inertiaについて大変参考になりました
- ロボットモデリング講習会:URDFの作成方法 by gbiggs
- マニピュレータのモデリングに関して解説されています