Raspberry Pi Mouse(移行中)

Raspberry Pi MouseのURDFモデル作成 その2

こんにちは!佐藤です。

今回は前回の続きでURDFのモデルの作成を行っていきます。

前回はとりあえず動かすことを目的としてパッケージを用意して、URDFを記述するところまで行いました。

URDFファイルについて

はじめに記述したURDFファイルの中身の説明をしたいと思います。
手前味噌で恐縮ですが、データ構造等はRT SHOP BLOGに詳しく書かれていますのでそちらをご参照ください!

ROSを使用したCRANE+の動かし方 その8 | RT Robot Shop Blog

前回記述したファイルを少し改良したものがこちらです。
本体の底面をグローバル座標の原点に設定していましたが、実際にはボディが床から1.85[mm]浮いています。
原点をbase_footprintとし、Z軸方向に0.00185[m]ずらした座標にbase_bodyをセットします。
(前回のエントリも修正いたしました。)

<robot name="raspimouse">
  <link name="base_footprint"/>

  <joint name="base_joint" type="fixed">
    <origin xyz="0 0 0.00185"/>
    <parent link="base_footprint"/>
    <child link="base_body"/>
  </joint>

  <link name="base_body">
    <visual>
      <geometry>
        <mesh filename="package://raspimouse_description/meshes/dae/base/RasPiMouse_base.dae"/>
      </geometry>
    </visual>
  </link>

  <joint name="left-wheel_joint" type="continuous">
    <origin xyz="0 0.0425 0.02215" rpy="-1.57 0 0"/>
    <axis xyz="0 0 1"/>
    <parent link="base_body"/>
    <child link="left-wheel"/>
  </joint>

  <link name="left-wheel">
    <visual>
      <geometry>
        <mesh filename="package://raspimouse_description/meshes/dae/wheel/RasPiMouse_wheel.dae"/>
      </geometry>
    </visual>
  </link>

  <joint name="right-wheel_joint" type="continuous">
    <origin xyz="0 -0.0425 0.02215" rpy="1.57 0 0"/>
    <axis xyz="0 0 1"/>
    <parent link="base_body"/>
    <child link="right-wheel"/>
  </joint>

  <link name="right-wheel">
    <visual>
      <geometry>
        <mesh filename="package://raspimouse_description/meshes/dae/wheel/RasPiMouse_wheel.dae"/>
      </geometry>
    </visual>
  </link>
</robot>

構造としては以下のようにベースとなる”base_footprint”、ボディの”base_body”があり、そこにホイールの”right-wheel”と”left-wheel”がそれぞれ”right-wheel_joint”と”left-wheel_joint”で接続されています。

$ check_urdf urdf/raspimouse.urdf 
robot name is: raspimouse
---------- Successfully Parsed XML ---------------
root Link: base_footprint has 1 child(ren)
    child(1):  base_body
        child(1):  left-wheel
        child(2):  right-wheel

“light-wheel_joint”では位置関係をこのように定義しています。

<origin xyz="0 0.0425 0.02215" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>

基準座標x,y,zを0,0.0425,0.02215と指定しています。ここで指定した座標は親である”base_body”の座標系で指定します。
ここで適切な位置を指定するためには、ホイールを駆動する軸の位置が原点から見てどの位置にあるのかをCADで測定しておくと大変便利でした。
また、作成した際にボディとは異なる座標系で作成したのでX軸周りに-90deg回転させたあと、回転後のZ軸を回転軸として指定しています。

launchファイルの作成

前回はこのようなコマンドで起動していました。

roslaunch urdf_tutorial display.launch model:='$(find raspimouse_description)/urdf/raspimouse.urdf' gui:=True

しかし、このままだとrvizの設定を保存した際に、urdf_tutorialのディレクトリの中にあるurdf.rvizに保存されてしまいます。
urdf_tutorialのurdf.rvizは/opt/ros/indigo/share/urdf_tutorialにありますのでそれをlaunch/config以下にコピーしておきます。

そこで、raspimouse_descriptionパッケージのlaunchディレクトリの中にdisplay.launchを作成します。

<launch>
<!-- arguments -->
<arg name="model" default="$(find raspimouse_description)/urdf/raspimouse.urdf"/>
<arg name="gui" default="True" />
<!-- prameters -->
<param name="robot_description" textfile="$(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 raspimouse_description)/launch/config/urdf.rviz" required="true" />
</launch>

これで以下のコマンドでlaunchできるようになりました。

roslaunch raspimouse_description display.launch

xacroファイルの作成

今までの設定ではホイールは回転しますし、ジョイントの角度を指定できる構造にはなっていますが、実機のように制御の入力値を受け取るようにはなっていません。
Gazeboでシミュレーションをするためには制御の入力値を受け取ることができるようにする必要があります。
まずは、「とりあえず動く」という状態にまで持っていけるようにするため、ros_controlを使えるようにする必要があります。
こちらがそのxacroファイルの一部です。raspimouse.urdf.xacroという名前でrobotsディレクトリに保存しています。

<?xml version="1.0"?>
<robot name="raspimouse" xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find raspimouse_description)/urdf/base/base.urdf.xacro"/>
<xacro:include filename="$(find raspimouse_description)/urdf/wheel/wheel.urdf.xacro"/>

<!-- =============== Link & Joint =============== -->
<!-- Base -->
<link name="base_footprint"/>
<xacro:base parent="base_footprint">
<origin xyz="0 0 0.00185"/>
</xacro:base>

<!-- Right Wheel -->
<xacro:wheel prefix="right" parent="base_body">
<origin xyz="0 -0.0425 0.02215" rpy="1.57 0 0"/>
<axis xyz="0 0 1"/>
</xacro:wheel>
<!-- Left Wheel -->
<xacro:wheel prefix="left" parent="base_body">
<origin xyz="0 0.0425 0.02215" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</xacro:wheel>

inertialタグで慣性行列や質量を定義することができるようになっています。
シミュレーションを行うにあたっては必要な値ですので、その計算する必要があります。
重心を基準として直方体の慣性モーメントを計算する場合、質量をM、横幅をa、奥行きをb、高さをcとしたとき、

ixx=M*(b^2+c^2)/12
iyy=M*(a^2+c^2)/12
izz=M*(a^2+b^2)/12

と表すことができます。
実際のボディは直方体ではありませんが、今回は直方体であるとみなして値を計算しました。

また、collisionタグで衝突検出領域を定義することができます。
作成しているボディと車輪のモデルはアームのモデルなどとは異なり、リンク同士でぶつかることはないと考えられます。
そのため、今回は衝突検出領域は定義しません。
こちらのファイルはbase.urdf.xacroという名前でurdf/baseに保存しています。

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:property name="M_PI" value="3.1415926535897931" />
  <xacro:property name="velocity_scale_factor" value="1.0"/>
  <xacro:macro name="base" params="parent *joint_origin">
    <joint name="base_joint" type="fixed">
      <insert_block name="joint_origin"/>
      <parent link="${parent}"/>
      <child link="base_body"/>
    </joint>
    <link name="base_body">
      <visual>
        <geometry>
          <mesh filename="package://raspimouse_description/meshes/dae/base/RasPiMouse_base.dae"/>
        </geometry>
      </visual>
      <inertial>
        <origin xyz="0 0 0.04"/>
        <mass value="0.724"/>
        <inertia ixx="0.0009920007" iyy="0.0013961737" izz="0.0016350937" />
      </inertial>
    </link>
  </xacro:macro>
</robot>

こちらがロボットの各車輪が速度指令を受け取って動くために必要なVelocityJointInterfaceの定義です。
wheel.transmission.xacroという名前でurdf/wheelに保存しています。

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="wheel_trans" params="prefix">
  <transmission name="${prefix}_wheel_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="${prefix}-wheel_joint">
      <hardwareInterface>VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="${prefix}-wheel_motor">
      <hardwareInterface>VelocityJointInterface</hardwareInterface>
    </actuator>
  </transmission>
  </xacro:macro>
</robot>

今回は紹介が多くなってしまったので次回はこのxacroファイルの改善と実際のraspimouseと同様に操作するためのコマンドの確認を行っていきます。
こちらのraspimouse_rosを使って左手法で迷路を探索するパッケージをサンプルとして取り扱う予定です。
https://github.com/ryuichiueda/raspimouse_lefthand

参考文献

タイトルとURLをコピーしました