yasunori.jp

Yasunori Toshimitsu | 利光泰徳

ホーム / ブログ / 自分のロボットをMu...


自分のロボットをMuJoCoでシミュレーションしよう!CADからMJCFを作る方法

2024年07月13日

この記事は、オープンソースのロボット物理エンジンのMuJoCoで、既存のロボットモデル(例えば、MuJoCo Menagerie)を試してみた上で、今度はあなた自身のロボットをMuJoCoでシミュレーションしてみたいと思っている方向けに書きました。MuJoCoは、ロボットモデルに用にMJCFというXMLフォーマットを使用しており、URDFフォーマットもサポートしています。CADモデルから直接URDFモデルに変換する変換スクリプトもいくつか存在しますが、個人的には、MJCFモデルをゼロから自分で書くほうがずっと簡単だと思います。自分で書くので、すべてのモデルパラメータを整合性を保ったまま管理できますし、思うほど複雑でもありません。そこでこの記事では、私がこれまでに知っている中で最も簡単に、CADで作成したロボットモデルをMuJoCoでシミュレーション可能な形式に手動で変換する方法をご紹介します!最後には、MJCFモデルをIsaacGymでも使えるようにする方法も解説します。

click here for the English version

サンプルモデル

公開済みの、参考となるMJCFモデルを載せておきます。この記事では取り上げられていないような、より高度な機能も実装されていたりします。複雑なモデルを作りたい場合は、まずは本記事で基本的な構造を実装した上で、以下のサンプルモデルを参考にするといいでしょう。

ステップ 1: お好みのCADソフトウェアでロボットを設計します

CAD上では関節が定義されていなくても(可動しなくても)大丈夫です。それぞれの関節はこれからMJCFファイル上で別途定義する必要があるからです。ここでは例として、Fusion 360を使用して非常にシンプルな、2関節のロボットアームのモデルを作ってみました。

このCADデザインを入手するには、Fusionオンラインハブにアクセスするか、.stepファイルをこちらからダウンロードしてください。このCADモデルには関節が定義されている必要はありませんが、各リンクのメッシュを別々にエクスポートできるように、各リンクの構造が個別のボディになっていることを確認してください。また、この記事で構築していく最終的なMJCFモデルのファイルは、この Google Drive フォルダまたはこの zipファイルから入手できます。

ステップ 2: STL メッシュの書き出し

CAD内の各リンクを個別の STL ファイルとしてエクスポートします(OBJ および MSH ファイル形式もサポートされています)。ここで、変換プロセスを簡単に実行するための鍵は、すべてのメッシュを同じ世界座標系で保存することです。使用する CADソフトによって異なりますが、少なくともFusion 360の場合は、以下の手順でこれを実現できます。

  1. エクスポートしたいコンポーネント以外のコンポーネントをすべて非表示にする(ツリーにある各ボディの「目」のアイコンをクリック)
  2. STL形式でエクスポート(左上のファイルアイコンをクリックし、「エクスポート…」を選択)
  3. 各ボディに対してこの手順を繰り返す

それぞれのメッシュが確実に同じ座標系で出力されたということを確認したい場合は、メッシュ編集ソフト(MeshLabなど)にすべてを読み込んだとき、正しく組み立てられた状態で表示されることを確認してください。

ステップ 3: XML の記述を開始します!

これ以降のステップでは、公式ドキュメントがあなたの味方です。長いですが、必要な情報はすべて記載されています。行き詰ったときは常に参照してください。 https://mujoco.readthedocs.io/en/latest/XMLreference.html

もう一つ、便利で重要なツールとして、mujocoのインストール時に一緒にインストールされる simulateというバイナリプログラムがあります。 (mujocoをpipでインストールした場合は、python -m mujoco.viewerで起動できます。) そのウィンドウにXMLファイルをドラッグ&ドロップすると、そのモデルが読み込まれます(または、XML内にエラーがある場合はそれを表示してくれます)。 XMLファイルを作成している間は、このシミュレータにしょっちゅうモデルを読み込んで、正常に動作しているか確認してください!

この「シミュレート」プログラムには、サイドバーに多くの機能が実装されています。これらの機能を最大限に活用してください。例えば、シミュレーションを一時停止(pause) / 実行(Run)したり(スペースバーでも切り替え可能)、シミュレーションをリセット(Reset)して初期状態に戻したり、XMLファイルを再読み込み(Reload)したり(XMLの内容を更新した場合に便利)することができます。 他のパネルも、アクチュエータの位置や接触力を可視化したり、重力などの物理パラメータを変更したりできます。すべてのツールをじっくりと試してみることをお勧めします。モデルのデバッグに大いに役立つはずです。

また、XMLの記述に不慣れな場合は、すべてのタグが正しく閉じられ、適切なインデントが設定されていることを確認するためのツールを使用することをお勧めします。VSCode をお使いの場合は、XML 拡張機能をインストールし、エディタで ctrl-shift-p を押してコマンドを開き、「フォーマット」→「XML」を選択して自動インデントを適用できます。

では、まずメッシュを読み込みましょう。my_robot.xmlというファイルを作成し、それと同じディレクトリにSTLファイルも保存します。

<mujoco model="really_simple_arm">
    <default>
        <!-- Fusion 360 の座標系を MuJoCo に変換します -->
        <geom type="mesh" xyaxes="1 0 0 0 0 1"/>
    </default>
    <asset>
        <!-- Fusionはデフォルトでmm単位のメッシュを出力しますが、MuJoCoではmに変換する必要があります。そのため、スケーリングが必要です -->
        <mesh name="base" file="base.stl" scale="0.001 0.001 0.001"/>
        <mesh name="link1" file="link1.stl" scale="0.001 0.001 0.001"/>
        <mesh name="link2" file="link2.stl" scale="0.001 0.001 0.001"/>
    </asset>
    <worldbody>
        <body name="base">
            <geom mesh="base"/>
            <body name="link1">
                <geom mesh="link1"/>
                <body name="link2">
                    <geom mesh="link2"/>
                </body>
            </body>
        </body>
    </worldbody>
</mujoco>

これを MuJoCo に読み込むと、早速ロボットが表示されます!

<default>要素内の<geom type="mesh" xyaxes="1 0 0 0 0 1"/>行が何をしているのか疑問に思うかもしれません。ここでは、ボディ内の各<geom>インスタンスで再定義されない限り使用される、geom要素のデフォルトの属性を設定しています。MuJoCoはロボットにおける一般的な座標系(x軸は前方、z軸は上方)を使用していますが、これはCADソフトウェアの座標軸とは異なります。なので、回転変換xyaxes="1 0 0 0 0 1"が必要です。左がCADの座標軸、右がMuJoCoの座標軸です(RGBの色はそれぞれXYZ軸に対応しています)。

ステップ 4: ジョイントを追加します

CADソフトウェアで各関節のXYZ位置を測定し、各<body>タグの下に関節を追加します。

例えば、最初のジョイントは、XMLファイルの<body name="link1">の下に以下の行を追加することで定義できます(ここでも、座標軸の順番が異なることに注意してください):

<joint name="joint_1" pos="0.1 -0.015 0.05" axis="0 1 0" limited="true" range="-45 45"/>

2つ目のジョイントは、<body name="link2">要素の後に以下を追加することで追加できます。

<joint name="joint_2" pos="0.1583 -0.01 0.1994" axis="0 1 0" limited="true" range="-90 90"/>

シミュレーションを一時停止すると、右側のパネルで各関節の角度をスライダーで調整することができます。

この時点では、(もしあなたのCADモデルが私のように雑に設計されていて、内部干渉があるなら)各ボディ間で大きな衝突力が発生しているかもしれません。これは、「Rendering」タブの「Contact Point」/「Contact Force」を有効にすることで視覚化できます。

とりあえず、simulateのサイドバーのPhysics → Disable Flagsで「Contact」を選択すると、すべての接触を無効にできます。(XMLのオプションに<flag contact="disable">を設定すれば、常に無効にすることもできます)より上手な解決法はあとのステップで紹介します。

ステップ 5: アクチュエータを追加

次に、各関節のアクチュエータを定義します。MJCFではいくつかの異なるタイプのアクチュエータを利用できますが、ここではPD制御を関節に適用する位置アクチュエータを使用します。<worldbody>と同じ階層にこれを追加します。

    <actuator>
        <position name="joint_1" joint="joint_1" ctrllimited="true" ctrlrange="-0.78 0.78" kp="1" kv="0.1"/>
        <position name="joint_2" joint="joint_2" ctrllimited="true" ctrlrange="-1.57 1.57" kp="1" kv="0.1"/>
    </actuator>

これで、全体XMLは次のように記述できます(XMLを簡潔にするために、いくつかのデフォルトを設定しました)。

<mujoco model="really_simple_arm">
    <compiler angle="radian"/> <!-- 角度の定義にはラジアンを使用 -->
    <option>
        <!-- 注:mujoco バージョン 3 より前のバージョンを使用する場合は、代わりに <option collision="predefined"/> を設定してください -->
        <flag contact="disable"/>
    </option>
    <default>
        <!-- XMLを完結にするため、デフォルト属性を設定します -->
        <!-- xy軸による変換を設定することで、Fusion 360の座標系をMuJoCoに変換します-->
        <geom type="mesh" xyaxes="1 0 0 0 0 1"/>
        <joint type="hinge" limited="true" axis="0 1 0"/>
        <!-- kp は比例ゲイン、kv はダンピングゲイン -->
        <position ctrllimited="true" kp="1" kv="0.1"/>
    </default>
    <asset>
        <!-- Fusionはデフォルトでmm単位のメッシュを出力しますが、MuJoCoではmに変換する必要があります。そのため、スケーリングが必要です -->
        <mesh name="base" file="base.stl" scale="0.001 0.001 0.001"/>
        <mesh name="link1" file="link1.stl" scale="0.001 0.001 0.001"/>
        <mesh name="link2" file="link2.stl" scale="0.001 0.001 0.001"/>
    </asset>
    <worldbody>
        <body name="base">
            <geom mesh="base"/>
            <body name="link1">
                <joint name="joint_1" pos="0.1 -0.015 0.05" range="-0.78 0.78"/>
                <geom mesh="link1"/>
                <body name="link2">
                    <joint name="joint_2" pos="0.1583 -0.01 0.1994" range="-1.57 1.57"/>
                    <geom mesh="link2"/>
                </body>
            </body>
        </body>
    </worldbody>

    <actuator>
        <position name="joint_1" joint="joint_1" ctrlrange="-0.78 0.78"/>
        <position name="joint_2" joint="joint_2" ctrlrange="-1.57 1.57"/>
    </actuator>
</mujoco>

ステップ 6: 接触の除外を設定します

内部干渉が発生した場合にすべての接触を無効にする方法を示しましたが、これは当然、最適な解決策ではありません。このような内部力を回避しながらも他の場所では接触を計算できるようにする方法は、接触除外ペア(Contact exclusion pair)を隣接するボディ間に設定することです。これを設定することで、<flag contact="disable"/>要素を削除でき、リンク2とベースがぶつかったときに、衝突が正しく計算されるようになりました!

<contact>
    <exclude body1="base" body2="link1"/>
    <exclude body1="link1" body2="link2"/>
</contact>

ステップ 7: リアルなシミュレーションのために物理的特性を確認する

シミュレーションを実際のロボットと同じ動作にするには、調整しなければならない要素がたくさんあり、この投稿ではとても紹介しきれません(もはやこれで一つの研究分野です)。例えば、関節の減衰とアクチュエータのゲインを調整することで、アクチュエータの応答を実際のロボットの動作に一致させることができます。

とりあえず、質量を確認してみましょう。 デフォルトでは、水の密度をもとに、メッシュ形状から各<geom>の質量の値が自動的に計算されます。 すでに実際のロボットがある場合には、<geom>の質量として、実際に計測した質量を設定することをお勧めします。そうすれば、ジオメトリの形状に基づいて回転慣性モーメントが自動的に計算されます。 https://mujoco.readthedocs.io/en/latest/XMLreference.html#body-geom

Inertiaを視覚化すると慣性ボックスが表示され、質量設定の確認に役立ちます。

繰り返しになりますが、STLファイルを含む最終的なMJCFモデルのすべてのファイルは、このGoogle Driveフォルダまたはこのzipファイルから入手できます。

モデルを IsaacGym で使用する場合

IsaacGymでロボットをシミュレートし、強化学習をしてみたいという人もいると思うのでその方向けの解説も最後に書いておきます。

IsaacGymはMJCFをサポートしていますが、IsaacGym用のモデルを記述するのは、これはこれで難しい問題です。というのも、IsaacGymの MJCF パーサーの実装は中途半端なもので、MuJoCo で動作するすべてのモデルが IsaacGym で動作するわけではないからです。そしてほとんどの場合、サポートされていないMJCFの機能を使用していても教えてくれません!

フォーラムに行けば、ユーザーが報告したMJCF読み込み時の問題を見ることができます:https://forums.developer.nvidia.com/search?q=MJCF

ここではすべてをご紹介できませんが、IsaacGymで動作しないことが判明しているMJCFの機能をいくつかご紹介します。

私自身、ロボットが IsaacGym で正しく表示されない原因を突き止めるのに苦労しました。IsaacGym で動作する既存のMJCF モデル(この記事の冒頭でご紹介したものなど)を確認し、それらのモデルに含まれる要素のみを使用することをお勧めします。

なので、この記事で作ったモデルをIsaacGymで使いたい場合は、geomのデフォルトの向きを定義しているxyaxes="1 0 0 0 1"を、代わりにクォータニオンを使うように変更する必要がります(チュートリアルでは、より直観的に理解できるxyaxesを使っていました) そのため、quat="0.7071068 0.7071068 0 0"に変更する必要があります。 この3D Rotation Converterというサイトは、このような変換を計算するのにとても便利なのですが、MuJoCoのクォータニオンはw x y zの順番であり、コンバーターで表示されるx y z wとは異なることに注意してください。

IsaacGymのサンプルプログラム(e.g. actor_scaling.py)にロボットを追加して、ロボットが正しくロードされていることを確認してください: ところが、メッシュの凸包(Convex hull)だけが表示されているのがわかるでしょう。これはIsaacGymの接触計算に使われる凸包です。実際のメッシュを見たい場合は、IsaacGymEnvsのShadow Handのモデルなどの例に従って、衝突計算用と可視化用の2つのクラスのgeomを作成する必要があります。サンプルモデルディレクトリにあるmy_robot_isaacgym.xmlには、これらの変更がすでに適用されているので、試してみてください。

ちなみに、asset_options.vhacd_enabled = Trueに設定すると、凸分解 (Convex decomposition)が自動的に衝突メッシュに適用されるので、形状が多少凸でなくてもロボットのシミュレーションができます(この「秘密の」オプションの存在はごく最近知りました。もっと前から知りたかった!)。

IsaacGymで何ができるのか気になる方は、私たちが昨年IsaacGymとFaive Hand(研究室内で設計されたロボットハンド)を使って取り組んだ強化学習プロジェクトの「Get the Ball Rolling」 project websiteをぜひ見てみてください(宣伝)。 また、私たちのフレームワークを使ってあなた自身のロボットハンドに強化学習を適用することに興味があれば、チューリッヒ工科大学のReal World Roboticsクラスの一環として作成したチュートリアルビデオをご覧ください(また宣伝):


ここで紹介した方法は、少なくとも正しい構造を持つ最初のモデルを作成するのには役立ちますが、もちろん、シミュレーションの「リアルさ」を高めるために改善すべき要素は、摩擦、減衰、アクチュエータのパラメータなど、他にもたくさんあります。基本的なモデルが完成した後も、モデルを常に確認し、調整して改善していく必要があります。それでも、このチュートリアルが、ロボットシミュレータの世界への第一歩を踏み出す一助になれば幸いです!



New posts


自分のロボットをMuJoCoでシミュレーションしよう!CADからMJCFを作る方法
2024.07/13
IPv6だとSoftEther/SSTPでVPNを経由して接続してくれなかった問題への対処
2024.04/13
【ライブレポート】Ado 世界ツアー「Wish」ヨーロッパ最終公演(ドイツ・デュッセルドルフ)に行ってきた
2024.03/17
日本の未来は明るい、気がする
2024.03/03

more...