Raspberry Pi Mouse(移行中)

Gazeboで走るRasPiMouse その3

こんにちは。佐藤です。

前回はGazeboでRasPiMouseが動かせることを確認しました。

概要

今回は見た目を少し改良し、まっすぐに走ることができるようにします。

見た目の改良

前回まではこのように真っ白でした。
Screenshot from 2016-08-15 19:10:56

これをこのように色を付けて実物にもう少し近づけてみます。
Screenshot from 2016-08-16 17:31:26

簡単にできる方法はいくつかあります。

  • テクスチャをマッピングしたメッシュデータを用意する
  • xacroでメッシュデータにテクスチャをマッピングする
  • 色付きのメッシュデータを用意する
  • xacroでメッシュデータの色を指定する

今回はstlを用意する時点で色ごとに分割して出力し、Colladaファイルへ変換する際に色をつけます。
変換方法についてはこちらをご覧ください。
Raspberry Pi MouseのURDFモデル作成 その1 | RT MicroMouse

このようにいくつかのパーツに分けて色を付けたあと、
Screenshot from 2016-08-16 17:42:19

最後にまとめてColladaファイルとしてエクスポートします。
Screenshot from 2016-08-16 17:42:38

このデータをxacroあるいはurdfで指定することで色付きのモデルができます。

ホイールの回転方向修正

前回はx軸方向へ進むコマンドを送信してもその場で旋回してしまっていました。

rostopic pub -1 /raspimouse/diff_drive_controller/cmd_vel geometry_msgs/Twist  '{linear:  {x: 0.1, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 0.0}}'

20160815_3

回転軸が逆なようです。
今回のモデルで軸を定義しているのではraspimouse_descriptionの中にあるrobots/raspimouse.urdf.xacroとurdf/wheel/wheel.urdf.xacroです。
これらを編集します。

編集箇所は以下のとおりです。右回りに回転するはずです。
軸の原点をロール角を+90度回転させた方の回転軸を逆向きにしました。

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

ちなみに、前回も紹介しましたがwheelというマクロは次のように定義されています。

  <xacro:macro name="wheel" params="prefix parent *joint_origin *joint_axis">
  <joint name="${prefix}_wheel_joint" type="continuous">
    <insert_block name="joint_origin"/>
    <insert_block name="joint_axis"/>
    <parent link="${parent}"/>
    <child link="${prefix}_wheel"/>
    <limit effort="70" velocity="15"/>
    <safety_controller  k_velocity="10" />
    <dynamics damping="1.0" friction="1.0" />
  </joint>
  <link name="${prefix}_wheel">
    <visual>
      <geometry>
        <mesh filename="package://raspimouse_description/meshes/dae/wheel/RasPiMouse_wheel.dae"/>
      </geometry>
    </visual>
    <collision>
        <geometry>
          <mesh filename="package://raspimouse_description/meshes/dae/wheel/RasPiMouse_wheel.dae"/>
        </geometry>
    </collision>
      <inertial>
        <origin xyz="-0.000107 0 0.002875"/>
        <mass value="${wheel_mass}"/>
        <inertia ixx="0.000002208187" ixy="0.000000000001" iyy="0.00000218412" ixz="0.000000004787" iyz="0.000000000003" izz="0.000004078299"/>
      </inertial>
  </link>
  </xacro:macro>

このように回転軸の向きを統一することによってロボットをまっすぐ進めることができるようになりました。
20160816_2

次回はセンサと走らせるためのコマンドについて触れていきます。

補足

重心位置について

前回はInventorで慣性行列を計算し、URDFの定義に書き加えました。
重心はホイールの回転軸上ではなく、若干後ろ側に寄っています。
また、ホイールの回転軸が固定されておらず、フリーになっています。
そのため、ボディが後ろに回転しようとし、床と触れた結果ホイールが回転して前に少しずつ進んでしまうという状態です。
(早送りにしています。)
20160816_1

ボディの摩擦係数を変えてみたり、回転軸の摩擦を変えてみたりしましたが、どれもうまく行きませんでした。
ボディの摩擦係数を変えると、回転し始める際にかなり揺れます。
滑らないほど回転軸の摩擦を大きくするとcmd_vel geometry_msgs/Twistを送った際にホイールが外れてしまいました。
そこで、微少量後退するコマンドを周期的に送ったところ、全くと言っていいほど動かなくなりました。

rostopic pub -r 1 /raspimouse/diff_drive_controller/cmd_vel geometry_msgs/Twist  '{linear:  {x: -0.001, y: 0.0, z: 0.0}, angular: {x: 0.0,y: 0.0,z: 0.0}}'

今のところdiff_drive_controllerを使用していますが、実際のRasPiMouseとはコマンドが異なるのでros_control側で軸を固定することができるようにする必要がありそうです。

tk-WARNINGについて

Gtk-WARNING **: module_path にはテーマ・エンジンがありません: “pixmap”,

と言われることがあります。
gtk2-engines-pixbufが足りていないので、以下のコマンドでインストールできます。

sudo apt-get install gtk2-engines-pixbuf

参考文献

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