クワマイでもできる

クワマイでもわかる

xacroでロボットを書く[2] - transmissionとgazebo

f:id:kuwamai:20190331203442p:plain 前回は対向二輪型ロボットのモデルをxacroで書いた。

今回はGAZEBOで走らせるために動力と摩擦係数の設定をする。具体的にはTransmission elementでホイールを速度制御できるように設定し、Gazebo elementでロボットの摩擦係数を設定する。

動作環境

  • Ubuntu16.04
  • ROS Kinetic Kame
  • GAZEBO 7.0.0

練習の記録

今回やってることはこちらのリポジトリに公開してます。

下記手順はnavigation_practiceディレクトリで行う前提で話を進める。

Transmission element

ホイールが回転するように動力の設定をwheel.transmission.xacroに記述する。
Transmission elementの記述方法について詳しくはこちら。

$ vim mabot_description/urdf/wheel/wheel.transmission.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="wheel_trans" params="prefix interface">
    <transmission name="${prefix}_wheel_trans">
      <type>transmission_interface/SimpleTransmission</type>

      <joint name="${prefix}_wheel_joint">
        <hardwareInterface>${interface}</hardwareInterface>
      </joint>
      
      <actuator name="${prefix}_wheel_motor">
        <hardwareInterface>${interface}</hardwareInterface>
      </actuator>
    </transmission>
  </xacro:macro>
</robot>

wheel.urdf.xacrowheel.transmission.xacroを読み込ませるよう書き加える。

$ vim mabot_description/urdf/wheel/wheel.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find mabot_description)/urdf/wheel/wheel.transmission.xacro" />
<!--省略-->

書いたTransmissionをmabot.urdf.xacroの最後の方に書き加える。
今回はホイールの速度を制御したいのでVelocityJointInterfaceを使った。
他には力制御をするEffortJointInterface、位置制御をするPositionJointInterfaceがある。

$ vim mabot_description/robots/mabot.urdf.xacro
  <!--省略-->
  <!-- ===========  Transmission ============ -->
  <xacro:wheel_trans prefix="right" interface="hardware_interface/VelocityJointInterface" />
  <xacro:wheel_trans prefix="left" interface="hardware_interface/VelocityJointInterface" />
</robot>

Gazebo element

Pluginのインストール

下記のコマンドで必要なPluginをインストールする。

$ sudo apt-get install ros-kinetic-gazebo-ros-control
$ sudo apt-get install ros-kinetic-ros-control ros-kinetic-ros-controllers

Gazebo elementの記述

さっきインストールしたPluginをmabot.urdf.xacroの最後の方に書き加える。

$ vim mabot_description/robots/mabot.urdf.xacro
  <!--省略-->
  <!-- =============== Gazebo =============== -->
  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>mabot</robotNamespace>
    </plugin>
  </gazebo>
</robot>

物体の性質を記述

Gazebo elementでは物体の摩擦係数、硬さ、色とか設定できる。今回はwheelが滑らないように摩擦係数を大きめに、casterはよく滑るように摩擦係数を0にした。摩擦係数はmu1mu2で設定する。
その他の要素は下記リンクに詳しく書いてある。

$ vim mabot_description/urdf/body/body.gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="base_gazebo">
    <gazebo reference="base_link">
      <mu1>0.05</mu1>
      <mu2>0.05</mu2>
    </gazebo>
  </xacro:macro>
</robot>
$ vim mabot_description/urdf/caster/caster.gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="caster_gazebo">
    <gazebo reference="caster_link">
      <mu1>0.0</mu1>
      <mu2>0.0</mu2>
    </gazebo>
  </xacro:macro>
</robot>
$ vim mabot_description/urdf/wheel/wheel.gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="wheel_gazebo" params="prefix">
    <gazebo reference="${prefix}_wheel">
      <mu1>1.0</mu1>
      <mu2>1.0</mu2>
    </gazebo>
  </xacro:macro>
</robot>

各部品にGazebo elementの設定を読み込ませるように書き加える。

$ vim mabot_description/urdf/body/body.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find mabot_description)/urdf/body/body.gazebo.xacro" />
<!--省略-->
$ vim mabot_description/urdf/caster/caster.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find mabot_description)/urdf/caster/caster.gazebo.xacro" />
<!--省略-->
$ vim mabot_description/urdf/wheel/wheel.urdf.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find mabot_description)/urdf/wheel/wheel.gazebo.xacro" />
<!--省略-->

mabot.urdf.xacroの最後の方に書き加えることでロボットにGazebo要素が追加される。

$ vim mabot_description/robots/mabot.urdf.xacro
  <!--省略-->
  <xacro:base_gazebo/>
  <xacro:wheel_gazebo prefix="right" />
  <xacro:wheel_gazebo prefix="left" />
  <xacro:caster_gazebo/>
</robot>

これでロボットがシミュレータ上で走るために必要な設定が終わった。今度はシミュレータ上で走らせる。