ROS URDFファイルによるモデル作成
この記事の目的
ROSでURDFファイルを記述してロボットモデルを作成する方法についてまとめる
1. URDF(Unified Robot Description Format)ファイルについて
ROSではロボットの構造(車輪や関節、各種センサの位置関係や可動範囲など)をURDFというXML形式で規定されたフォーマットで記述する。 URDFでモデルを記述することで、rvizやGazebooでロボットモデルを画面上で可視化しながら動作確認ができ開発がしやすくなる。 URDFファイルの記述方法についてはROS公式チュートリアルに記載されている。 wiki.ros.org
本記事では、1/10サイズのラジコンにkinect v1センサを搭載している車両を例にURDFファイルの記述方法を説明する。 www.tamiya.com
●シャーシ長385mm、シャーシ幅187mm 厚さ 50mm (タイヤ中心が車体と接続していると仮定) ●ホイールベース257mm ●タイヤ幅/径=前後とも24/64mm ●Kinectセンサ(サイズは幅275×奥行き6.0×高さ8.0mm)は車体最前方に取り付け
2. URDFの記述
URDFファイルの最も基本的なサンプルは公式チュートリアルに下記のように示されている。
<robot name="test_robot"> <link name="link1" /> <link name="link2" /> <link name="link3" /> <link name="link4" /> <joint name="joint1" type="continuous"> <parent link="link1"/> <child link="link2"/> </joint> <joint name="joint2" type="continuous"> <parent link="link1"/> <child link="link3"/> </joint> <joint name="joint3" type="continuous"> <parent link="link3"/> <child link="link4"/> </joint> </robot>
上記において、robot nameはロボット名(任意)を設定する。 linkはロボットの剛体部分、ジョイントはlinkを結合する関節部分を設定する。
jointのtypeは下記の意味を持つ。今回描画しようとしている例ではタイヤはcontinuous、センサーはfixedを使う。
設定 | 意味 |
---|---|
continuous | 軸方向に制限なく回転する |
revolute | 軸方向に回転(上下限制限あり) |
prismatic | 軸方向にスライドする機構 |
floating | 6自由度(回転+スライド) |
planar | 軸の上下前後に動く |
fixed | 固定されている |
joint内部のparent、childは親子関係を設定する。(車体を親、センサー・タイヤを子に設定すればよい)
次に、linkの形状・色の設定について説明する。車体を立方体として記述する場合は下記の様に設定する。
<?xml version="1.0"?> <robot name="my_robo"> <link name="base_link"> <visual> <geometry> <box size="0.385 0.187 0.05"/> </geometry> <origin xyz="0 0 0.034" rpy="0 0 0"/> <material name="gray"> <color rgba="0.8 0.8 0.8 1"/> </material> </visual> <collision> <geometry> <box size="0.385 0.187 0.05"/> </geometry> </collision> </link> </robot>
link_name "base_link"はROSでロボットの車体中心に設定する名称である。 geometryのboxsizeに立方体のx y z方向の大きさを設定する。 (xが進行方向 = 縦方向であることに注意) origin xyzが立方体の中心座標を設定する。 また、materialとしてrvizで表示される色をRGB + 透明度として設定している。 その下ではcollisionとして衝突判定に使う領域サイズを設定できる。
上記に左前輪のタイヤを設定するには下記のように記述する。
<link name="left_front_wheel_link"> <visual> <geometry> <cylinder radius="0.034" length="0.024"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="black"> <color rgba="0.1 0.1 0.1 1"/> </material> </visual> </link> <joint name="left_front_wheel_joint" type="fixed"> <parent link="base_link"/> <child link="left_front_wheel_link"/> <origin rpy="-1.5707 0 0" xyz="0.128 0.105 0.034"/> <axis xyz="0 0 1"/> </joint> </robot>
円柱はcylinderとして設定し、半径と高さ をタイヤに合わせて設定する。 jointで車体にタイヤを取り付ける角度をrpyと位置をxyzで指定する。 車体に縦方向に回転させたいので -PI/2をroll角に設定し、xにはホイールベースの半分、yはシャシー幅+タイヤ幅で設定した。 同様に4つ分のタイヤとセンサーを設定すると下記のようになる。
<robot name="my_robo"> <link name="base_link"> <visual> <geometry> <box size="0.385 0.187 0.05"/> </geometry> <origin xyz="0 0 0.034" rpy="0 0 0"/> <material name="gray"> <color rgba="0.8 0.8 0.8 1"/> </material> </visual> <collision> <geometry> <box size="0.385 0.187 0.05"/> </geometry> </collision> </link> <link name="left_front_wheel_link"> <visual> <geometry> <cylinder radius="0.034" length="0.024"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="black"> <color rgba="0.1 0.1 0.1 1"/> </material> </visual> </link> <joint name="left_front_wheel_joint" type="fixed"> <parent link="base_link"/> <child link="left_front_wheel_link"/> <origin rpy="-1.5707 0 0" xyz="0.128 0.105 0.034"/> <axis xyz="0 0 1"/> </joint> <link name="left_rear_wheel_link"> <visual> <geometry> <cylinder radius="0.034" length="0.024"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="black"> <color rgba="0.1 0.1 0.1 1"/> </material> </visual> </link> <joint name="left_rear_wheel_joint" type="fixed"> <parent link="base_link"/> <child link="left_rear_wheel_link"/> <origin rpy="-1.5707 0 0" xyz="-0.128 0.105 0.034"/> <axis xyz="0 0 1"/> </joint> <link name="right_front_wheel_link"> <visual> <geometry> <cylinder radius="0.034" length="0.024"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="black"> <color rgba="0.1 0.1 0.1 1"/> </material> </visual> </link> <joint name="right_front_wheel_joint" type="fixed"> <parent link="base_link"/> <child link="right_front_wheel_link"/> <origin rpy="1.5707 0 0" xyz="0.128 -0.105 0.034"/> <axis xyz="0 0 1"/> </joint> <link name="right_rear_wheel_link"> <visual> <geometry> <cylinder radius="0.034" length="0.024"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="black"> <color rgba="0.1 0.1 0.1 1"/> </material> </visual> </link> <joint name="right_rear_wheel_joint" type="fixed"> <parent link="base_link"/> <child link="right_rear_wheel_link"/> <origin rpy="1.5707 0 0" xyz="-0.128 -0.105 0.034"/> <axis xyz="0 0 1"/> </joint> <link name="kinect_vis"> <visual> <geometry> <box size="0.060 0.275 0.08"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="blue"> <color rgba="0.0 0.0 0.8 1"/> </material> </visual> </link> <joint name="kinect_vis" type="fixed"> <parent link="base_link"/> <child link="kinect_vis"/> <origin rpy="0 0 0" xyz="0.180 0.0 0.098"/> <axis xyz="0 0 1"/> </joint> </robot>
3. TFの発行とrvizでの可視化
rosで上記のurdfファイルを読み込みrvizで可視化することができる。
そのために、下記ツールが必要となるためapt-get でインストールする
sudo apt-get install ros-melodic-joint-state-publisher-gui
その後、下記のlaunchファイルを記述する。
<launch> <arg name="model" default="$(find vehivle_model_description)/car_model.urdf"/> <arg name="gui" default="False"/> <arg name="rvizconfig" default="$(find vehivle_model_description)/urdf.rviz"/> <param name="robot_description" command="$(find xacro)/xacro.py $(arg model)"/> <param name="use_gui" value="$(arg gui)"/> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/> <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>
このファイルでは、記述したurdf (car_model.urdfというファイル名で保存した)を読み込み、 rvizの起動とrosノード joint_state_publisher・robot_state_publisherの立ち上げを行っている。 joint_state_publisherとrobot_state_publisherはいずれもロボットの関節と座標系のtfを配信してrvizで表示するときに必要なツールである。
上記を実行後にrvizで座標系をbaselink に設定してDisplaysにtfとrobotmodelを選択すると正しく表示されることが確認できる。