環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 20.04 |
ROS | Noetic |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
前回に続いてxacroの使い方を説明していきます。
例4(macro:モジュール化)
urdfだと同じような記述を何度も繰り返す場合が多々あります。そこである程度同じ内容の記述をマクロ化できます。
ソースコード
<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<material name="red">
<color rgba="1.0 0.0 0.0 2.0"/>
</material>
<xacro:macro name="box_macro" params="suffix parent radius">
<joint name="${suffix}_joint" type="fixed">
<origin rpy="0 0 0" xyz="${0.5*cos(radians(radius))} ${0.5*sin(radians(radius))} 0"/>
<parent link="${parent}"/>
<child link="${suffix}_link"/>
</joint>
<link name="${suffix}_link">
<visual>
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
<material name="red"/>
</visual>
</link>
</xacro:macro>
<link name="base_link"/>
<xacro:box_macro suffix="box0" parent="base_link" radius="0"/>
<xacro:box_macro suffix="box1" parent="base_link" radius="30"/>
<xacro:box_macro suffix="box2" parent="base_link" radius="60"/>
<xacro:box_macro suffix="box3" parent="base_link" radius="90"/>
</robot>
-
<xacro:macro name="box_macro">
から</xacro:macro>
の間でマクロを定義します。 -
<xacro:macro name="box_macro" params="suffix parent radius">
のようにparams=の後ろにつなげることでマクロの引数を規定できます。マクロの定義の中では<link name="${suffix}_link">
のようにpropertyとしてふるまいます。 - 定義したマクロは
<xacro:box_macro suffix="box0" parent="base_link" radius="0"/>
のように呼び出すことができます。定義した引数をすべて指定しないとエラーになります。
実行
roscd vis_lecture/xacro/
roslaunch urdf_tutorial display.launch model:=basic4.xacro
箱を表示するマクロを作ってそれを4回呼び出すことで、上記のような表示ができました。
例5(インクルード)
basic4.xacroと同等のことをしますが、macroの定義のところをbasic5_h.xacroに書いて、それをbasic5.xacroからincludeします。
ソースコード
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<material name="red">
<color rgba="1.0 0.0 0.0 2.0"/>
</material>
<xacro:macro name="box_macro" params="suffix parent radius">
<joint name="${suffix}_joint" type="fixed">
<origin rpy="0 0 0" xyz="${0.5*cos(radians(radius))} ${0.5*sin(radians(radius))} 0"/>
<parent link="${parent}"/>
<child link="${suffix}_link"/>
</joint>
<link name="${suffix}_link">
<visual>
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
<material name="red"/>
</visual>
</link>
</xacro:macro>
</robot>
<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find vis_lecture)/xacro/basic5_h.xacro" />
<link name="base_link"/>
<xacro:box_macro suffix="box0" parent="base_link" radius="0"/>
<xacro:box_macro suffix="box1" parent="base_link" radius="30"/>
<xacro:box_macro suffix="box2" parent="base_link" radius="60"/>
<xacro:box_macro suffix="box3" parent="base_link" radius="90"/>
</robot>
<xacro:include filename="$(find vis_lecture)/xacro/basic5_h.xacro" />
でincludeをしています。$(find package_name)
でパッケージの絶対パスを取得できます。
実行
roscd vis_lecture/xacro/
roslaunch vis_lecture xacro_expand.launch model:=basic5.xacro
上のマクロ化と同様の表示ができます。
例6(launch時に与えるパラメーター)
今までの例では1つのxacroファイルからは決まった物体しか表示できません。
launch時にパラメーターを与える方法を説明します。
ソースコード
<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="length" default="1.0"/>
<material name="red">
<color rgba="1.0 0.0 0.0 2.0"/>
</material>
<link name="base_link"/>
<joint name="body_joint" type="fixed">
<origin rpy="0 0 0" xyz="$(arg length) 0 0"/>
<parent link="base_link"/>
<child link="body_link"/>
</joint>
<link name="body_link">
<visual>
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
<material name="red"/>
</visual>
</link>
</robot>
<xacro:arg name="length" default="1.0"/>
で外部から受け取る変数名を宣言します。defaultは必須ではないですが、が無いとlaunch時に未指定でエラーになります。"$(arg length)"
でこの変数を使います。${ }
で展開するxacroのpropertyとは違って、このargはrospackコマンドなので$(arg )
で展開するので注意です。
<launch>
<arg name="model" default="$(find vis_lecture)/xacro/basic6.xacro"/>
<arg name="rvizconfig" default="$(find vis_lecture)/config/xacro_expand.rviz" />
<arg name="length0" default="1.0" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model) length:=$(arg length0) --inorder" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
launchでは <param name="robot_description" command="$(find xacro)/xacro $(arg model) length:=$(arg length0) --inorder" />
の様ににタグのcommand属性の中でlength:=****
と指定します。--inorder
は最後に書かないとエラーになります。
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
roslaunch vis_lecture xacro_expand6.launch length0:=1.0
以下のようにオプションを変えて実行すると表示も変わります。
roslaunch vis_lecture xacro_expand6.launch length0:=2.0