
強化学習への道6 -ロボット強化学習2-
前回は2足歩行ロボットの強化学習に挑戦し、うまくいかないのでモータ単体のモデルを再検証検証しました。
トルク駆動のブラシレスモータモデルでモータ単体の角度変更 強化学習 Sim2Real実証を行いました。
トルク制御の強化学習結果を実機で堪能
ここにきてはじめてSim先行で結果を得た
つまり私が強化学習で実機駆動設計ができる人間になったということ#強化学習への道 #Sim2Real#ReinforcementLearning pic.twitter.com/7txvEuckX8— HomeMadeGarbage (@H0meMadeGarbage) May 19, 2025
ここではこのトルク指定モデルで2足歩行ロボットの強化学習の検証を実施します。
目次
2足歩行ロボット強化学習
トルク指定モデルを2足歩行ロボットに適応して直立姿勢を学習させてみた
観測
股関節基部の角度、角速度
モータの角度、角速度
行動
各モータトルク
立たん
モデルやモータ駆動に異常はないことは分かっているので
以下要確認
・角度、角速度算出式の検算 (軸間違ってないか?)
・各モータの回転方向の符号確認
・トルク足りないか?スケーリングして確認#強化学習への道#ReinforcementLearning pic.twitter.com/74lkAX1vY4— HomeMadeGarbage (@H0meMadeGarbage) May 20, 2025
全然立たない。。。
モータやロボのモデルが悪いのか、学習が悪いのか。。。
全然わからいので1個1個検証しますね。
モデル検証
まずはモデルを検証。
強化学習ではなくモデルを用いてPython上でPID制御でモータ角度→トルク変換して関節0°指定での直立を確認
1個づつ丁寧にやっていこう。実機と同じ気持ちで
まずはPID制御でモータ角度が0°になるように制御
問題なく立っているのでトルク不足はないみたいだね。実機でもちゃんと立って足踏みまで出来てるのだから当然だよね#強化学習への道#ReinforcementLearning pic.twitter.com/J21EfHK5A6
— HomeMadeGarbage (@H0meMadeGarbage) May 21, 2025
立つね。実機でも立つしロボモデルに大きな問題はなさそう。
学習検証
モデルに問題はないことが分かったので強化学習の報酬で色々試したところ
すこし立った!
立った#強化学習への道#ReinforcementLearning pic.twitter.com/wg3oN2mDSM
— HomeMadeGarbage (@H0meMadeGarbage) May 21, 2025
報酬は以下
1 2 3 4 5 6 7 8 |
reward = ( - pitch**2 - roll**2 - 0.1 * pitch_vel**2 - 0.1 * roll_vel**2 - 0.01 * np.sum(np.square(action)) # 省エネ項 + (1.0 if abs(pitch) < math.radians(1) and abs(roll) < math.radians(1) else 0.0) # ±1°ご褒美 ) |
股関節基部の角度(pitch, roll)とその角速度(pitch_vel, roll_vel)がゼロになるように学習
学習ステップも100万ステップ程に増やすと立ちだしました。
やっと立ったので学習の精度高めていこうと思ったのですが、、ふと思いました。
トルク制御では中間的な姿勢は学習させにくいのでは??と
やはりトルクではなく角度指定で動くロボモデルにして歩行などを学習するべきではと考えました。
(ブラシレスモータをただ回すだけならトルク指定のほうが実機にあうし実際Sim2Real結果も良好でしたが、今回は関節にギアかましてるしなぁ。。。)
再モータモデル化 BAM
角度指定のロボモデルを構築するに際し、またまたモータのモデル化から考えます。
以下のようにギア込みで1つのアクチュエータとしてモデル化してみたいと思います。
モータのモデル化については本強化学習の道のきっかけとなった Open_Duck_Mini projectの手法にならって実施しました。
BAM: Better Actuator Models というサーボモータのモデル化メソッドを使用します。
以下BAMのフローに沿ってモデル化
Recording raw data
ブラシレスモータとギアで振り子をつくって
sin(t * t) で振動させてログ録り
Recording raw data#強化学習への道#ReinforcementLearning pic.twitter.com/kOgZRWtOOP
— HomeMadeGarbage (@H0meMadeGarbage) May 28, 2025
指定角度、実角度、スピード、電流をログとして取得しBAMのモータモデル ERobを参考に Jsonファイルを生成した。
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 |
{ "mass": 0.088, "arm_mass": 0.106, "length": 0.113, "kp": 10, "damping": 3.0, "motor": "bldc56", "trajectory": "sin_time_square", "entries": [ { "timestamp": 0.001, "position": -0.227413, "speed": 0.0, "control": 2.477, "goal_position": 0.0, "torque_enable": true }, { "timestamp": 0.004, "position": -0.227139, "speed": -0.803302, "control": 2.319, "goal_position": 0.0, "torque_enable": true }, ・ ・ ・ { "timestamp": 6.137, "position": -0.410395, "speed": 1.601906, "control": 0.026, "goal_position": -0.0319, "torque_enable": true } ] |
Post-processing
測定ログJsonをモデルフィット用に時間等間隔に補間 (5msec)
1 |
python -m bam.process --raw data_raw --logdir data_processed --dt 0.005 |
Model fitting
モータモデルは仮でerob80_50を選択
フィッティングモデルはm1
1 |
python -m bam.fit --actuator erob80_50 --model m1 --logdir data_processed --method cmaes --output params/erob80_50/m1.json --trials 10000 |
m1モデル取得
1 2 3 4 5 6 7 8 9 10 |
{ "kt": 1.5863288175333292, "R": 3.4515291085867674, "armature": 0.0025937221542474756, "q_offset": -0.029173895245651768, "friction_base": 0.026932325922545804, "friction_viscous": 5.207239235979312, "model": "m1", "actuator": "erob80_50" } |
Plotting
実測ログと生成フィッティングモデルを比較
1 |
python -m bam.plot --actuator erob80_50 --logdir data_processed --sim --params params/erob80_50/m1.json |
角度 (angle)はバッチリ合っていますが電流(トルク)の波形が大きく異なっています。
実機振り子のアクチュエータがブラシレスモータにギアを介しているので駆動電流は一般的なモータモデルと異なるはしょうがないので、とりあえずこれでいいや。
MuJoCoモデルに変換
変換式 to_mujoco() に従ってm1モデルパラメータをMuJoCoアクチュエータ向けに変換
forcerange = vin * kt / R = 1.38
armature = armature = 0.0026
kp_mujoco = error_gain * kp * vin * max_pwm * kt / R = 13.79
damping = friction_viscous + kt**2 / R = 5.9364
frictionloss = friction_base = 0.0269
MuJoCoの関節ジョイントにpositionアクチュエータとして仕込みます。
1 2 3 4 |
<default> <joint damping="5.9364" frictionloss="0.0269" armature="0.0026"/> <position kp="13.79" kv="0.0" forcerange="-1.38 1.38"/> </default> |
実機と比較
まぁいいんじゃないかな
出来たモデルと実機の比較#強化学習への道#ReinforcementLearning pic.twitter.com/KuOdrMAKW9
— HomeMadeGarbage (@H0meMadeGarbage) May 29, 2025
2足歩行ロボット
作成したフィッティング関節モータモデルを2足歩行ロボットに展開
関節角度をpython上で指定して動かしてみた
やっと関節の角度指定で動くモデルができた
歩かせたいけどね#強化学習への道#ReinforcementLearning pic.twitter.com/T1O6uL2Oty— HomeMadeGarbage (@H0meMadeGarbage) May 31, 2025
これで関節角度指定による2足歩行ロボットモデルが完成しました。
おわりに
ここではモータをギアを含めたアクチュエータとしてモデルリングを実施して、関節角度指定による2足歩行ロボットモデルを完成させました。
次はこのモデルでロボット動作の強化学習を実施たいと思います。
いろいろ試行錯誤してここまで来たのでうまくいってほしいものです。
ほな