0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

実習ROS 2 xacroを使う2

Last updated at Posted at 2025-02-06

環境

本記事は以下の環境を想定して記述している。

項目
OS Ubuntu 22.04
ROS ROS 2 Humble

概要

このページでは、xacro(Xml mACRO)におけるマクロ機能の使い方を説明する。実習ROS 2 xacroを使う1で説明した定数や数式・条件式をマクロ機能と組み合わせることで、より簡単に、より分かりやすくxacroを記述できる。
このページは、ROS 2公式チュートリアルを参考に、ROS講座73 xacroを使う2の内容をROS 2対応させたものである。

前準備

前提条件

このチュートリアルは、実習ROS 2 Pub&Sub通信を実行していることを前提に、Pub&Sub通信のチュートリアルで作成したワークスペースros2_lecture_wsを利用する。
また、実習ROS 2 xacroを使う1の実施を前提とする。実習ROS 2 xacroを使う1で説明した、変数、数式、条件式の知識を前提に、より発展的な機能を解説する。

ROS 2パッケージの作成

パッケージxacro2およびxacroファイルを格納するディレクトリ/xacro、launchファイルを格納するディレクトリ/launchを作成する。

cd ~/ros2_lecture_ws/src
ros2 pkg create xacro2 --build-type ament_cmake --dependencies urdf_launch
mkdir ./xacro2/xacro
mkdir ./xacro2/launch

モジュール化

モジュール化の方法

  1. モジュールの定義
    モジュールは以下の形式で定義する。モジュールには任意の数の引数を設定できる。

    <xacro:macro name="*モジュール名*" params="*引数名1* *引数名2* ...">
      <モジュール内の処理>
    </xacro:macro>
    

    設定した引数は、モジュール内の処理の記述に利用できる。引数の値は以下のように記述すると利用できる。

    <"${*引数名*}">
    
  2. モジュールの利用
    定義したモジュールは以下のように書くと利用できる。

    <xacro:*モジュール名* *引数1*="*引数1の値*" *引数2*="*引数2の値*" .../>
    

モジュールを利用した例

モジュールの利用例として、xacroファイルmodule.xacroを作成する。このxacroファイルは、一辺が0.1mの大きさの立方体を、半径0.5mの円周上に30°間隔で4つ並べたものである。

<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  <material name="red">
    <color rgba="1.0 0.0 0.0 1.0"/>
  </material>
  
  <!--モジュールの定義-->
  <xacro:macro name="box_macro" params="prefix parent radius">
    <joint name="${prefix}_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="${prefix}_link"/>
    </joint>

    <link name="${prefix}_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 prefix="box0" parent="base_link" radius="0"/>
  <xacro:box_macro prefix="box1" parent="base_link" radius="30"/>
  <xacro:box_macro prefix="box2" parent="base_link" radius="60"/>
  <xacro:box_macro prefix="box3" parent="base_link" radius="90"/>
</robot>

module.xacro

  1. モジュールの定義
    このxacroでは、prefixparentradiusという3つの引数を持つマクロbox_macroを定義している。

    <!--モジュールの定義-->
    <xacro:macro name="box_macro" params="prefix parent radius">
      ...
    </xacro:macro>  
    

    モジュール内の処理では、受け取った引数を利用して、一辺が0.1mの立方体を1つ作成する。引数の利用箇所を以下に示す。

    • 引数prefixを利用して、ジョイント名とリンク名を設定する。

        <joint name="${prefix}_joint" type="fixed">
          ...
          <child  link="${prefix}_link"/>
        </joint>
      
        <link name="${prefix}_link">
          ...
        </link>  
      
    • 引数parentを利用して、ジョイントの親リンクを設定する。

          <parent link="${parent}"/>
      
    • 引数radiusを利用して、リンクの位置を設定する。

          <origin rpy="0 0 0" xyz="${0.5*cos(radians(radius))} ${0.5*sin(radians(radius))} 0"/>
      
  2. モジュールの利用
    以下の箇所でモジュールbox_macroを利用し、リンク、ジョイントの接頭辞をbox0box3としたリンクを4つ作成している。それぞれ、親リンクはbase_link、中心からの角度は0°~90°に設定した。
    この例のように、同じ処理を繰り返すときにモジュールを利用することで、繰り返し処理が簡単に記述できる。

    <!--モジュールの利用-->
    <xacro:box_macro prefix="box0" parent="base_link" radius="0"/>
    <xacro:box_macro prefix="box1" parent="base_link" radius="30"/>
    <xacro:box_macro prefix="box2" parent="base_link" radius="60"/>
    <xacro:box_macro prefix="box3" parent="base_link" radius="90"/>
    

RVizでの表示

作成したmodule.xacroをRViz上に表示すると以下のように表示される。立方体が4つ、円周上に並んでいることが分かる。

module.xacroの表示結果

インクルード

インクルードの使い方

以下のように記述することで、他のxacroファイルをインクルードできる。インクルードすると、インクルードしたxacroファイルの処理が実行される。

<xacro:include filename="*インクルードするファイルパス*" />

インクルードを利用した例

インクルードを利用したxacroファイルinclude.xacroを作成する。このxacroファイルは、先ほど作成したmodule.xacroをインクルードする。その後、module.xacroで作成したモジュールを利用して、新たなリンクを作成している。

<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  <!--別のxacroファイルをインクルード-->
  <xacro:include filename="$(find xacro2)/xacro/module.xacro" />

  <!--インクルードしたxacroファイルのモジュールを利用-->
  <xacro:box_macro prefix="box4" parent="base_link" radius="120"/>
  <xacro:box_macro prefix="box5" parent="base_link" radius="150"/>
  <xacro:box_macro prefix="box6" parent="base_link" radius="180"/>
</robot>

include.xacro

以下の箇所でmodule.xacroをインクルードする。これにより、モジュールbox_macroが定義され、base_linkおよびbox0box3が作成される。

<!--別のxacroファイルをインクルード-->
<xacro:include filename="$(find xacro2)/xacro/module.xacro" />

以下の箇所では、インクルードしたモジュールbox_macroを利用している。中心角が120°~180°の位置に、box4box6という名前の立方体を3つ作成している。

<!--インクルードしたxacroファイルのモジュールを利用-->
<xacro:box_macro prefix="box4" parent="base_link" radius="120"/>
<xacro:box_macro prefix="box5" parent="base_link" radius="150"/>
<xacro:box_macro prefix="box6" parent="base_link" radius="180"/>

RVizでの表示

作成したinclude.xacroをRViz上に表示すると以下のように表示される。module.xacroで作成した立方体4つに加えて、include.xacroで作成した立方体3つが作成されていることが分かる。

include.xacroの表示結果

launchファイルで変数を渡す

これまでの例では、1つのxacroファイルからは決まった物体しか表示できなかった。xacroの変数機能を使うことで、launchファイルからxacroファイルに値を渡し、その値に基づいたモデルを作成できる。

変数の使い方

  1. 変数の定義
    xacroファイルに以下の形式で記述すると、変数を定義できる。定義した変数にはデフォルト値を設定できる。

    <xacro:arg name="*変数名*" default="*変数のデフォルト値*"/>
    
  2. 変数の利用
    変数を利用する際は以下の通りに記述する。

    $(arg *変数名*)
    

変数を使用した例

変数を利用したxacroファイルlaunch_arg.xacroを作成する。このxacroファイルは、変数lengthの値を使って座標中心と立方体の距離を設定する。

<robot name="test_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  <!--デフォルト値0.0で変数lengthを定義-->
  <xacro:arg name="length" default="0.0"/>

  <material name="red">
    <color rgba="1.0 0.0 0.0 1.0"/>
  </material>

  <link name="base_link"/>

  <joint name="body_joint" type="fixed">
    <!--変数lengthを利用-->
    <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>

launch_arg.xacro

  1. 変数の定義
    以下の箇所で、デフォルト値0.0で変数lengthを定義している。

    <!--デフォルト値0.0で変数lengthを定義-->
    <xacro:arg name="length" default="0.0"/>
    
  2. 変数の利用
    以下の箇所で変数を利用している。body_linkのx軸上の位置を、変数の値に設定している。

    <!--変数lengthを利用-->
    <origin rpy="0 0 0" xyz="$(arg length) 0 0"/>
    

launchファイルの作成

ディレクトリ/xacro2/launchにlaunchファイルxacro_launch_with_length.launch.pyを作成する。このlaunchファイルは、xacroファイルの変数に値を設定して、モデルをRVizに表示する。
このlaunchファイルを起動すると、robot_state_publisherとrviz2の2つのROSノードを起動する。robot_state_publisherはロボットの情報をrviz2に配信するノードである。

from ament_index_python.packages import get_package_share_path

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import Command, LaunchConfiguration

from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue

def generate_launch_description():
    ld = LaunchDescription()

    default_model_path = str(get_package_share_path('xacro2')) + '/xacro/launch_arg.xacro'
    rviz_config_path = str(get_package_share_path('urdf_launch')) + '/config/urdf.rviz'

    # launchファイルのパラメータ設定
    model_arg = DeclareLaunchArgument(name='model', default_value=default_model_path,
                                    description='Absolute path to robot urdf file')
    length_arg = DeclareLaunchArgument(name='length_value', default_value="1.0",
                                    description='length between center and robot')
    
    # robot_state_publisherのパラメータ設定
    # launchファイルのパラメータ"length_value"の値を、xacroのパラメータ"length"に設定
    robot_description = ParameterValue(
        Command(['xacro ', LaunchConfiguration('model'), ' length:=', LaunchConfiguration('length_value')]),
        value_type=str
    )

    # robot_state_publisherとrviz2をLaunchDescriptionに追加
    robot_state_publisher_node = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        parameters=[{'robot_description': robot_description}]
    )

    rviz_node = Node(
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        output='screen',
        arguments=['-d', rviz_config_path],
    )

    ld.add_action(model_arg)
    ld.add_action(length_arg)
    ld.add_action(robot_state_publisher_node)
    ld.add_action(rviz_node)

    return ld

xacro_launch_with_length.launch.py

  1. launchファイルのパラメータ
    作成したlaunchファイルは、パラメータmodellength_valueを持つ。
    modelは起動するモデルの絶対パスで、デフォルト値はlaunch_arg.xacroのパスとした。また、length_valueはxacroファイルに渡すlengthの値で、デフォルト値は1.0に指定した。
    ros2 launchコマンドや別のlaunchファイルからこのlaunchファイルを起動するとき、これらのパラメータに値を設定できる。

    # launchファイルのパラメータ設定
    model_arg = DeclareLaunchArgument(name='model', default_value=default_model_path,
                                    description='Absolute path to robot urdf file')
    length_arg = DeclareLaunchArgument(name='length_value', default_value="1.0",
                                    description='length between center and robot')
    
  2. xacroファイルの変数の設定
    以下の箇所で、robot_state_publisherに渡すパラメータを記述している。モデルのパスには、launchファイルのパラメータmodelの値を設定した。また、xacroファイルの引数lengthには、launchファイルのパラメータlength_valueの値を設定している。
    この設定により、launchファイルからxacroファイルの変数に値を渡すことができる。

    # robot_state_publisherのパラメータ設定
    # launchファイルのパラメータ"length_value"の値を、xacroのパラメータ"length"に設定
    robot_description = ParameterValue(
        Command(['xacro ', LaunchConfiguration('model'), ' length:=', LaunchConfiguration('length_value')]),
        value_type=str
    )
    

また、作成したlaunchファイルを起動するために、CMakeLists.txtとpackage.xmlに以下の行を追加する。

CMakeLists.txt

 # install launch files
 install(
   DIRECTORY
+  launch
   xacro
   DESTINATION share/${PROJECT_NAME}/
 )

package.xml

+ <exec_depend>ros2launch</exec_depend>

RVizで表示

作成したlaunch_arg.xacroをRVizで表示する。
はじめに、これまでと同様にurdf_launchパッケージのdisplay.launchを使用する。display.launchはxacroファイルの変数に値を渡さずにRVizで表示する。従って、xacroファイルの引数lengthにはデフォルト値が適用される。

ros2 launch urdf_launch display.launch.py urdf_package:=xacro2 urdf_package_path:=./xacro/launch_arg.xacro 

display.launchlaunch_arg.xacroを表示すると以下のようになる。座標の中心からの距離に、デフォルト値(0.0m)が適用されていることが分かる。

launch_arg.xacroの表示結果(デフォルト)

つぎに、作成したlaunchファイルxacro_launch_with_length.launch.pyのデフォルト値を利用して、xacroファイルをRVizに表示する。ワークスペースでビルドしてオーバーレイを取得した後、以下のコマンドを実行する。

ros2 launch xacro2 xacro_launch_with_length.launch.py

launchすると、以下のウィンドウが表示される。座標の中心からの距離に、launchファイルのデフォルト値(1.0m)が適用されていることが分かる。

launch_arg.xacroの表示結果(launchデフォルト)

さいごに、launchファイルのパラメータlength_valueに2を設定してlaunchする。以下のコマンドを実行する。

ros2 launch xacro2 xacro_launch_with_length.launch.py length_value:=2

launchすると以下のウィンドウが表示される。座標の中心からの距離に、launch時に設定した値(2.0m)が適用されていることが分かる。

launch_arg.xacroの表示結果(length_value=2)

参考

0
0
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?