ふるお〜と!- FullAuto

AI・ロボットが普及しBI(ベーシックインカム)が早急に実現されることを願う元ニートのブログ

ふるお〜と!-FullAuto

ロボットを組み立ててSDFで記述して動かしてみた

VR空間でロボットパーツを個別に作成

BlenderXRでVR空間で作成することができます。 nullpo24.hatenablog.com

作成したオブジェクトはCOLLADA(.dae)として出力します(「File」→「Export」→「Collada(.dae)」)。

ロボット組み立て

新しくBlenderを立ち上げ出力したCOLLADA(.dae)を全てインポートします。
スケーツの調整と複製を行います。 f:id:nullpo24:20190611212445p:plain

VR空間内でパーツの位置を調整します。
また、全てのパーツは床より上(z>=0)になるようにしておきます。 f:id:nullpo24:20190611213219p:plain

COLLADA(.dae)はオブジェクトの座標の位置も保存される仕様です。
したがって、SDFで記述してGazeboで表示する際、全てのLink(剛体)のposeタグの要素を〔0 0 0 0 0 0〕(x y z ロール ピッチ ヨー)にすれば上の画像のように表示されます。

Jointの座標は自分で測る必要があります。

Joint座標測定

右上にあるWireframeアイコンをクリックします。 f:id:nullpo24:20190611222440p:plain

設計書があれば、Joint部の座標は導き出せそうです。
しかし、上のロボットはVR内で適当に作成し、配置したオブジェクトの集合体なのでJoint部の座標を測定します。
私はVR内で球体を作成し、それをJoint部に配置して、右下に表示されるLocation(座標)をメモっていきました。

f:id:nullpo24:20190614223903p:plain
球体の座標が右に表示される

f:id:nullpo24:20190614223556p:plain
各Jointの座標

これで、Jointのposeの要素を得ることができました。(とりあえず少数第3位まで[mm])

各パーツをCOLLADA(.dae)で個別に出力します。
エクスポート時に左下にあるSelection Onlyにチェックを入れれば選択したものだけ出力することができます。

f:id:nullpo24:20190614225412p:plain
Selection Only にチェック

パンドラワールド(SDF)を作成

pandra.world

<?xml version="1.0"?>
<sdf version="1.4">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
    </include>
    <include>
      <uri>model://sun</uri>
    </include>

    <model name="my_mesh1">
      <static>false</static>
      <link name="body">
        <visual name="visual">
          <geometry>
            <mesh><uri>file://Body.dae</uri></mesh>
          </geometry>
        </visual>
        <collision name="collision">
          <geometry>
            <mesh><uri>file://Body.dae</uri></mesh>
          </geometry>
        </collision>
      </link>

      <!-- 左前脚-->
      <link name="front_left_parts1">
        <visual name="visual">
          <geometry>
            <mesh>
              <uri>file://FrontLeftParts1.dae</uri>
            </mesh>
          </geometry>
        </visual>
        <collision name="collision">
          <geometry>
            <mesh>
              <uri>file://FrontLeftParts1.dae</uri>
            </mesh>
          </geometry>
        </collision>
      </link>

      <link name="front_left_leg">
        <visual name="visual">
          <geometry>
            <mesh>
              <uri>file://FrontLeftLeg.dae</uri>
            </mesh>
          </geometry>
        </visual>
        <collision name="collision">
          <geometry>
            <mesh>
              <uri>file://FrontLeftLeg.dae</uri>
            </mesh>
          </geometry>
        </collision>
      </link>

      <link name="front_left_parts2">
        <visual name="visual">
          <geometry>
            <mesh>
              <uri>file://FrontLeftParts2.dae</uri>
            </mesh>
          </geometry>
        </visual>
        <collision name="collision">
          <geometry>
            <mesh>
              <uri>file://FrontLeftParts2.dae</uri>
            </mesh>
          </geometry>
        </collision>
      </link>

      <link name="front_left_tire">
        <visual name="visual">
          <geometry>
            <mesh>
              <uri>file://FrontLeftTire.dae</uri>
            </mesh>
          </geometry>
        </visual>
        <collision name="collision">
          <geometry>
            <mesh>
              <uri>file://FrontLeftTire.dae</uri>
            </mesh>
          </geometry>
        </collision>
      </link>

      <!-- 右前脚 -->
          省略
      <!-- 左後脚-->
          省略
      <!-- 右後脚 -->
          省略

       <!-- Joints -->
      <!-- 左前脚 -->
      <joint name="joint_front_left1" type="revolute">
        <parent>body</parent>
        <child>front_left_parts1</child>
        <pose>-0.631 0.467 1.194 0 0 0</pose>
        <axis>
          <xyz>0 0 1</xyz>
        </axis>
      </joint>

      <joint name="joint_front_left2" type="revolute">
        <parent>front_left_parts1</parent>
        <child>front_left_leg</child>
        <pose>-1.293 0.615 1.303 0 0 0</pose>
        <axis>
          <xyz>0 0 1</xyz>
        </axis>
      </joint>

      <joint name="joint_front_left3" type="revolute">
        <parent>front_left_leg</parent>
        <child>front_left_parts2</child>
        <pose>-1.623 0.678 0.764 0 0 0</pose>
        <axis>
          <xyz>0 0 1</xyz>
        </axis>
      </joint>

      <joint name="joint_front_left4" type="revolute">
        <parent>front_left_parts2</parent>
        <child>front_left_tire</child>
        <pose>-1.150 0.697 0.452 0 0 0</pose>
        <axis>
          <xyz>0 0 1</xyz>
        </axis>
      </joint>

      <!-- 右前脚 -->
          省略
      <!-- 左後脚 -->
          省略
      <!-- 右後脚 -->
          省略

    </model>
  </world>
</sdf>

Jointの設定は公式のチュートリアルのままにしてみました。

実行(gazeboシミュレーション)

$ gazebo pandra.world

アレ...

f:id:nullpo24:20190614231338g:plain

Limitやfixedを追加

nullpo24.hatenablog.com

碇ゲンドウ「不自由をやろう」

f:id:nullpo24:20190616114756g:plain