
強化学習への道4 -ロボットSimモデル作成-
前回はブラシレスモータによるリアクションホイール姿勢制御モジュールの強化学習結果を実機に移行してSim2Realを楽しみました。
実機でも倒立動作を確認することができ強化学習の有用性を体感することができました。
ここでは同じブラシレスモータを用いた2足歩行ロボットの強化学習を目指してシミュレーションモデルを制作しましたので報告いたします。
目次
2足歩行ロボット
強化学習の次のテーマは製作途中となっていた1脚4自由度の2足歩行ロボットです。
足踏み動作までは確認済みです。
強化学習によってこのロボットの各種動作の生成を目指します。
前回の姿勢制御モジュールで得た知識が大いに活きるのではと考えております。
まずは片足から
まずは片足のかかと動作をMoJuCoで確認しました。
姿勢制御モジュールの時と同様にFusion360の設計STLファイルを取り込んでつなげるだけだろと考えておりました。。。
しかし。。。またアクチュエータ動作を仕込んでないのに勝手にホイールが暴れたり
接触していないはずのスネまで勝手に動く始末。。。
アクチュエータ仕込んでないのにホイール暴れる。。
小ギア入れてないのにスネまで動く
怖い。。#MuJoCo#強化学習への道 #ReinforcementLearning pic.twitter.com/Y0GCW2soNv— HomeMadeGarbage (@H0meMadeGarbage) May 14, 2025
この謎の動作に苦しみ、足元の1関節のモデルを作るだけでかなりの時間を消費しました( ノД`)
Xで教えてもらった
上の動画をXにアップしたところ有識者の方にいろいろ教えていただきました。
モデルが接触してるのではないとのこと
MoJuCoで”c”入力で接触が可視化されるらしい
Check for self collision! You can press “c” to see them in the viewer
— Antoine Pirrone (@antoinepirrone) May 14, 2025
モデル同士はCADデータ上では接触してないんだけどなぁと思いつつ
教えてもらった通りに見てみると。。
ありがとうございます。
やってみました。これってぶつかってるってことですかね?
CAD構造的には接触してないのですが pic.twitter.com/Xz6GlBQBAc— HomeMadeGarbage (@H0meMadeGarbage) May 14, 2025
なぜか接触してた。。
なんでだろ?当たり判定がCADモデル寸法より大きいのかな???
これを報告すると
< exclude >で衝突を無効化できるとのこと
Yes there are some self collisions between the motor and the gear it seems. You can use <exclude> to ignore them. How did you define the coupling between the motor and the gear in the mjcf description ?
— Antoine Pirrone (@antoinepirrone) May 14, 2025
以下のようにモータのホイールとスネモデルの接触を無視するように指定
1 2 3 |
<contact> <exclude body1="legL" body2="wheelL1"/> </contact> |
無事に解決し異常動作はなくなりました!
Thank you so so much!!
excludeで治りました。この動く現象に悩まされていたため
モータの方にはギアはまだ仕込んでいませんでした。今のところギア同士を接触させての物理動作はむずかしいかなと思っていますがどうでしょうか?
gear_linkでギア比指定してソフトでやろうかと考えていました。 pic.twitter.com/ryPpzSc4Ef
— HomeMadeGarbage (@H0meMadeGarbage) May 14, 2025
教えていただき本当にありがとうございました。
コレは絶対に自分では解決できなかった。
完成
モータの設定も記述して足元モデルが完成
やっとスネまでのリンクができた
干渉無視してるから通り抜けるけどね。。
強化学習時にはPythonで可動範囲制限するから問題ないはず#MuJoCo #強化学習への道 #ReinforcementLearning pic.twitter.com/yNHQy6ZTqE— HomeMadeGarbage (@H0meMadeGarbage) May 14, 2025
実機ではブラシレスモータに小さいギア(歯数10)でスネ(歯数56)を動かしているのですが
シミュレータで物理的にギア接触動作はできないので equality / joint機能でソフトで数理的にギア比を指定して処理しました。
1 2 3 |
<equality> <joint name="gear_link" joint1="wheelL1_joint" joint2="legL_joint" polycoef="0 -5.6 0 0 0"/> </equality> |
スネと足底の接続部の joint の 摩擦は適当に damping=”0.01″ としました。
この辺はSim2Realの段で詳細調整かなと考えています。
シミュレーションモデル製作中
ひと節できればあとは根気の作業よ#MuJoCo #強化学習への道 #ReinforcementLearning pic.twitter.com/rSPSxYVfJm
— HomeMadeGarbage (@H0meMadeGarbage) May 14, 2025
PythonでPIDで角度指定して動作させてみました。
製作したMuJoCoモデルをPIDで角度指定
実機とどこまで合ってるか判断難しいけど
一旦これでロボット組むわしばらくまたパソコン カタカタ作業で憂鬱だけど
勉めて強いるのが勉強である#強化学習への道#ReinforcementLearning pic.twitter.com/WTOZMgI3xv— HomeMadeGarbage (@H0meMadeGarbage) May 15, 2025
Simのモータのトルク定数と回転部の摩擦は前回の姿勢制御モジュールの時の値をそのまま使用しました。
PID値も適当でモデルが実機とどこまで合っているのか判断難しいですが、
一旦これでロボット組みます。
おいおい調整しますー
ロボットモデル制作
足のモデル制作でかなり手こずりましたが、あとは同じ作業の繰り返しですので
ロボットを組んて行きます。
両足完成
サバ#強化学習への道 #ReinforcementLearning pic.twitter.com/5KDGykvZRx
— HomeMadeGarbage (@H0meMadeGarbage) May 15, 2025
ロボ完成!
でけた#強化学習への道 #MuJoCo#ReinforcementLearning pic.twitter.com/zonl820MD0
— HomeMadeGarbage (@H0meMadeGarbage) May 15, 2025
PythonのPID角度制御で全モータ0°設定で立つことも確認できました。
各モータをPID制御で0°指定
これが本当に強化学習で歩くようになるんだべか?
いまのところ何をすればいいのか分かってない勉強する#強化学習への道 #MuJoCo #ReinforcementLearning pic.twitter.com/9a2vrfLGcM
— HomeMadeGarbage (@H0meMadeGarbage) May 15, 2025
MJCF
参考までにロボの MJCF (MuJoCo XMLフォーマットファイル)
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 |
<mujoco model="robo"> <option timestep="0.01"/> <asset> <mesh name="hip_mesh" file="assets/hip.stl"/> <mesh name="hipL_mesh" file="assets/hipL.stl"/> <mesh name="hipR_mesh" file="assets/hipR.stl"/> <mesh name="motorL4_mesh" file="assets/motorL4.stl"/> <mesh name="wheelL4_mesh" file="assets/wheelL4.stl"/> <mesh name="motorR4_mesh" file="assets/motorR4.stl"/> <mesh name="wheelR4_mesh" file="assets/wheelR4.stl"/> <mesh name="motorL1_mesh" file="assets/motorL1.stl"/> <mesh name="wheelL1_mesh" file="assets/wheelL1.stl"/> <mesh name="footL_mesh" file="assets/footL.stl"/> <mesh name="legL1_mesh" file="assets/legL1.stl"/> <mesh name="motorL2_mesh" file="assets/motorL2.stl"/> <mesh name="wheelL2_mesh" file="assets/wheelL2.stl"/> <mesh name="legL2_mesh" file="assets/legL2.stl"/> <mesh name="motorL3_mesh" file="assets/motorL3.stl"/> <mesh name="wheelL3_mesh" file="assets/wheelL3.stl"/> <mesh name="motorR1_mesh" file="assets/motorR1.stl"/> <mesh name="wheelR1_mesh" file="assets/wheelR1.stl"/> <mesh name="footR_mesh" file="assets/footR.stl"/> <mesh name="legR1_mesh" file="assets/legR1.stl"/> <mesh name="motorR2_mesh" file="assets/motorR2.stl"/> <mesh name="wheelR2_mesh" file="assets/wheelR2.stl"/> <mesh name="legR2_mesh" file="assets/legR2.stl"/> <mesh name="motorR3_mesh" file="assets/motorR3.stl"/> <mesh name="wheelR3_mesh" file="assets/wheelR3.stl"/> </asset> <worldbody> <light name="light1" pos="1 0 3" dir="-1 0 -1" directional="true"/> <body name="hip" pos="0 0 0"> <joint type="free"/> <inertial pos="0.0000000595 0.0 0.224732" mass="0.035226" diaginertia="2.349e-5 2.194e-5 4.137e-5"/> <geom type="mesh" mesh="hip_mesh"/> <body name="motorL4" pos="0 0 0"> <inertial pos="-0.012 -0.028367 0.224732" mass="0.032193" diaginertia="3.288e-6 5.549e-6 3.287e-6"/> <geom type="mesh" mesh="motorL4_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelL4" pos="0 0 0"> <joint name="wheelL4_joint" type="hinge" axis="0 1 0" pos="-0.012 -0.0532 0.224732" damping="0.00005"/> <inertial pos="-0.012 -0.034279 0.224732" mass="0.041898" diaginertia="8.321e-6 1.506e-5 8.317e-6"/> <geom type="mesh" mesh="wheelL4_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="motorR4" pos="0 0 0"> <inertial pos="0.012 0.028366 0.224732" mass="0.032193" diaginertia="3.288e-6 5.549e-6 3.287e-6"/> <geom type="mesh" mesh="motorR4_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelR4" pos="0 0 0"> <joint name="wheelR4_joint" type="hinge" axis="0 1 0" pos="0.012 0.0532 0.224732" damping="0.00005"/> <inertial pos="0.012 0.034278 0.224732" mass="0.041898" diaginertia="8.321e-6 1.506e-5 8.317e-6"/> <geom type="mesh" mesh="wheelR4_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="hipL" pos="0 0 0"> <joint name="hipL_joint" type="hinge" axis="0 1 0" pos="0.033 -0.0531 0.224732" damping="0.01"/> <inertial pos="0.046498 -0.015878 0.230476" mass="0.044212" diaginertia="2.963e-5 2.667e-5 4.068e-5"/> <geom type="mesh" mesh="hipL_mesh"/> <body name="legL2" pos="0 0 0"> <joint name="hipL2_joint" type="hinge" axis="1 0 0" pos="0 0 0.225" damping="0.01"/> <inertial pos="0.079398 -0.009148 0.178513" mass="0.040399" diaginertia="4.799e-5 4.256e-5 1.543e-5"/> <geom type="mesh" mesh="legL2_mesh"/> <body name="motorL3" pos="0 0 0"> <inertial pos="0.072634 0.0 0.192" mass="0.032193" diaginertia="5.549e-6 3.288e-6 3.287e-6"/> <geom type="mesh" mesh="motorL3_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelL3" pos="0 0 0"> <joint name="wheelL3_joint" type="hinge" axis="1 0 0" pos="0 0 0.192" damping="0.00005"/> <inertial pos="0.066722 0.0 0.192" mass="0.041898" diaginertia="1.506e-5 8.321e-6 8.317e-6"/> <geom type="mesh" mesh="wheelL3_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="legL1" pos="0 0 0"> <joint name="legL2_joint" type="hinge" axis="1 0 0" pos="0 0 0.145" damping="0.01"/> <inertial pos="0.06317 -0.005839 0.099086" mass="0.039233" diaginertia="4.579e-5 4.088e-5 1.379e-5"/> <geom type="mesh" mesh="legL1_mesh"/> <body name="motorL2" pos="0 0 0"> <inertial pos="0.070366 -0.0165 0.116421" mass="0.032193" diaginertia="5.548676e-6 3.288408e-6 3.287449e-6"/> <geom type="mesh" mesh="motorL2_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelL2" pos="0 0 0"> <joint name="wheelL2_joint" type="hinge" axis="1 0 0" pos="0 -0.0165 0.116421" damping="0.00005"/> <inertial pos="0.076278 -0.0165 0.116421" mass="0.041898" diaginertia="1.506176e-5 8.321359e-6 8.316901e-6"/> <geom type="mesh" mesh="wheelL2_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="footL" pos="0 0 0"> <joint name="legL1_joint" type="hinge" axis="1 0 0" pos="0 0 0.065" damping="0.01"/> <inertial pos="0.072513 0.0 0.017941" mass="0.04908" diaginertia="7.2602e-5 3.1938e-5 5.6188e-5"/> <geom type="mesh" mesh="footL_mesh"/> <body name="motorL1" pos="0 0 0"> <inertial pos="0.072634 0.000 0.032" mass="0.032193" diaginertia="5.5487e-6 3.2884e-6 3.2874e-6"/> <geom type="mesh" mesh="motorL1_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelL1" pos="0 0 0"> <joint name="wheelL1_joint" type="hinge" axis="1 0 0" pos="0 0 0.032" damping="0.00005"/> <inertial pos="0.066722 0.000 0.032" mass="0.041898" diaginertia="1.5062e-5 8.3214e-6 8.3169e-6"/> <geom type="mesh" mesh="wheelL1_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> </body> </body> </body> </body> <body name="hipR" pos="0 0 0"> <joint name="hipR_joint" type="hinge" axis="0 1 0" pos="-0.033 0.0531 0.224732" damping="0.01"/> <inertial pos="-0.046498 0.015877 0.230476" mass="0.044212" diaginertia="2.963e-5 2.667e-5 4.068e-5"/> <geom type="mesh" mesh="hipR_mesh"/> <body name="legR2" pos="0 0 0"> <joint name="hipR2_joint" type="hinge" axis="1 0 0" pos="0 0 0.225" damping="0.01"/> <inertial pos="-0.079398 -0.009142 0.178512" mass="0.040399" diaginertia="4.799e-5 4.256e-5 1.543e-5"/> <geom type="mesh" mesh="legR2_mesh"/> <body name="motorR3" pos="0 0 0"> <inertial pos="-0.072634 0.000006 0.191999" mass="0.032193" diaginertia="5.549e-6 3.288e-6 3.287e-6"/> <geom type="mesh" mesh="motorR3_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelR3" pos="0 0 0"> <joint name="wheelR3_joint" type="hinge" axis="1 0 0" pos="0 0 0.192" damping="0.00005"/> <inertial pos="-0.066722 0.000006 0.191999" mass="0.041898" diaginertia="1.506e-5 8.321e-6 8.317e-6"/> <geom type="mesh" mesh="wheelR3_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="legR1" pos="0 0 0"> <joint name="legR2_joint" type="hinge" axis="1 0 0" pos="0 0 0.145" damping="0.01"/> <inertial pos="-0.06317 -0.005833 0.099084" mass="0.039234" diaginertia="4.579e-5 4.089e-5 1.379e-5"/> <geom type="mesh" mesh="legR1_mesh"/> <body name="motorR2" pos="0 0 0"> <inertial pos="-0.070366 -0.016494 0.11642" mass="0.032193" diaginertia="5.549e-6 3.288e-6 3.287e-6"/> <geom type="mesh" mesh="motorR2_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelR2" pos="0 0 0"> <joint name="wheelR2_joint" type="hinge" axis="1 0 0" pos="0 -0.0165 0.116421" damping="0.00005"/> <inertial pos="-0.076278 -0.016494 0.11642" mass="0.041898" diaginertia="1.506e-5 8.321e-6 8.317e-6"/> <geom type="mesh" mesh="wheelR2_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> <body name="footR" pos="0 0 0"> <joint name="legR1_joint" type="hinge" axis="1 0 0" pos="0 0 0.065" damping="0.01"/> <inertial pos="-0.072513 0.000006 0.01794" mass="0.04908" diaginertia="7.260e-5 3.194e-5 5.619e-5"/> <geom type="mesh" mesh="footR_mesh"/> <body name="motorR1" pos="0 0 0"> <inertial pos="-0.072634 0.000006 0.031999" mass="0.032193" diaginertia="5.549e-6 3.288e-6 3.287e-6"/> <geom type="mesh" mesh="motorR1_mesh" rgba="0.8 0.8 0.85 1"/> <body name="wheelR1" pos="0 0 0"> <joint name="wheelR1_joint" type="hinge" axis="1 0 0" pos="0 0 0.032" damping="0.00005"/> <inertial pos="-0.066722 0.000006 0.031999" mass="0.041898" diaginertia="1.506e-5 8.321e-6 8.317e-6"/> <geom type="mesh" mesh="wheelR1_mesh" rgba="0.8 0.8 0.85 1"/> </body> </body> </body> </body> </body> </body> </body> <geom type="plane" size="5 5 0.1" pos="0 0 0" rgba="0.0 0.5 0.0 1"/> </worldbody> <contact> <exclude body1="legL1" body2="wheelL1"/> <exclude body1="legL2" body2="wheelL2"/> <exclude body1="hipL" body2="wheelL3"/> <exclude body1="hipL" body2="wheelL4"/> <exclude body1="legR1" body2="wheelR1"/> <exclude body1="legR2" body2="wheelR2"/> <exclude body1="hipR" body2="wheelR3"/> <exclude body1="hipR" body2="wheelR4"/> </contact> <actuator> <motor name="wheel_actL1" joint="wheelL1_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actL2" joint="wheelL2_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actL3" joint="wheelL3_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actL4" joint="wheelL4_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actR1" joint="wheelR1_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actR2" joint="wheelR2_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actR3" joint="wheelR3_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> <motor name="wheel_actR4" joint="wheelR4_joint" ctrlrange="-1.0 1.0" gear="0.0265"/> </actuator> <equality> <joint name="gear_linkL1" joint1="wheelL1_joint" joint2="legL1_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkL2" joint1="wheelL2_joint" joint2="legL2_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkL3" joint1="wheelL3_joint" joint2="hipL2_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkL4" joint1="wheelL4_joint" joint2="hipL_joint" polycoef="0 -8.0 0 0 0"/> <joint name="gear_linkR1" joint1="wheelR1_joint" joint2="legR1_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkR2" joint1="wheelR2_joint" joint2="legR2_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkR3" joint1="wheelR3_joint" joint2="hipR2_joint" polycoef="0 -5.6 0 0 0"/> <joint name="gear_linkR4" joint1="wheelR4_joint" joint2="hipR_joint" polycoef="0 -8.0 0 0 0"/> </equality> </mujoco> |
おわりに
ここではブラシレスモータ2足歩行ロボットの強化学習シミュレーション用のモデルを制作しました。
次回はいよいよロボットの強化学習を実施します。
今のところどうなるのか全く想像もつきませんが、いつものことなので気にせず邁進します。
それではまた