
強化学習への道2 -強化学習開始-
前回は強化学習に出会い勉強することを決意いたしました。
まずは物理シミュレーションエンジンMoJuCoの環境を整え使い方を学びました。
強化学習の初手のテーマとしてブラシレスモータによるリアクションホイール1軸姿勢制御モジュール(SHISEGYO-1)を選択し、MoJuCoで倒立動作を確認しました。
ここではついに強化学習に挑戦します。
目次
強化学習 環境構築
前回は姿勢制御モジュールのSim用モデルを制作して、古典制御の手動ゲイン調整で倒立動作をMoJuCo上で確認しました。
リアクションホイール
手動でパラメータ調整して倒立実現
もう実機と同じ感覚やね 職人だから俺さていよいよ強化学習すっか#MuJoCo #強化学習への道 pic.twitter.com/U2s99RkPdU
— HomeMadeGarbage (@H0meMadeGarbage) May 8, 2025
これによって割と現実的なSim用モデルができたという感触を得ました。
ここでは古典制御ではなく強化学習による倒立動作を目指します。
Python環境構築
強化学習用の環境を整えました (全部 ChatGPTに聞いた)。
構成は以下のとおり
MuJoCo + Gymnasium + Stable-Baselines3
この3つの役割はこんな感じ:(以下ほぼChatGPTによる文言)
MuJoCo(Multi-Joint dynamics with Contact)
→ リアルな物理挙動を計算してくれる物理エンジン。
摩擦、接触、慣性なんかも正確にシミュレートできる。
Gymnasium(旧OpenAI Gym)
→ 強化学習環境の“インターフェース”。
reset() と step() で状態と報酬をやりとりする形式を統一してくれる。
Stable-Baselines3(SB3)
→ PPOやSACなど、有名どころの強化学習アルゴリズムを簡単に使えるライブラリ。
Gym形式の環境にポリシーを学習させるだけで、すぐに学習が始まる。
今回はPPO = Proximal Policy Optimization(近接方策最適化)を使用
必要パッケージを以下でインストール
pip install mujoco gymnasium stable-baselines3[extra] numpy matplotlib
姿勢制御モジュール強化学習
リアクションホイール姿勢制御モジュールのモデルをそのまま流用して強化学習を実施しました。
強化学習は報酬 [reward]を設定して試行錯誤しながら所望の動作を目指す手法です。
ここでは
theta: 本体の傾き(Y軸)
omega_y: 本体のY軸角速度
wheel_speed: ホイールの回転速度
を入力(観測 [observation])としてモータトルク(行動 [action])を得て 倒立を目指します。
強化学習用PythonライブラリGymnasium環境で報酬や学習手法を定義します。
とりあえず報酬を以下のようにしてみました。
1 2 3 4 5 6 |
reward = float( -theta**2 # 傾きペナルティ - 0.001 * omega_y**2 # 揺れ防止 - 0.001 * wheel_speed**2 # ホイール回しすぎたらペナルティ + 1.0 * (abs(theta) < 0.1) # 直立してたらボーナス! ) |
Gymnasium環境で定義した報酬と学習手法に基づいて強化学習アルゴリズムであるPPOで学習させました。
50000ステップ程学習させるとzipファイルで学習結果が得られました。
古いMX250搭載のノートPCで実行しましたが2分ほどで学習は終了しました。
学習結果でモデルを動かしてみました。
遂に強化学習実施
MuJoCo + Gymnasium + Stable-Baselines3 (PPO) の構成報酬コレで学習
reward = float(
-theta**2 # 傾きペナルティ
– 0.001 * omega_y**2 # 揺れ防止
– 0.001 * wheel_speed**2 # ホイール回しすぎたらペナ
+ 1.0 * (abs(theta) < 0.1) #… pic.twitter.com/KgHNCiqKNI— HomeMadeGarbage (@H0meMadeGarbage) May 9, 2025
たった!なんか立ってる!すげー!
遂に強化学習ができてしまいました。
外乱に耐えうる倒立学習
外乱耐性を確認するために先ほどの学習結果のSimに対して姿勢制御モジュール筐体の地面接地ロール軸に±0.01Nmの外乱をランダムに印可してみました(この外乱の強さが現実的なのかはおいおい調べる)。
外乱として筐体を軽くつついてみたら全然ダメ
学習の段階でが入れるべきだったみたい#強化学習への道 pic.twitter.com/Yt4BzS1MgO
— HomeMadeGarbage (@H0meMadeGarbage) May 9, 2025
すぐ倒れたwww
モータも全然回ってないし。。
ちなみに前回の古典フィードバックで手動でゲイン調整したSimに同様の外乱を加えると実機のようにしっかりホイールを回して倒立を維持します。
ちなみに古典フィードバックで手動でゲイン調整したヤツだと筐体つついても立ってる#強化学習への道 pic.twitter.com/om1VB9TDUD
— HomeMadeGarbage (@H0meMadeGarbage) May 9, 2025
報酬設計
強化学習は環境が正常に整えられれば、あとはいかに報酬を設定するかがキモであると感じました。
報酬設計の勘所を掴むのにかなり苦心しました。
最初の報酬では倒立時の動作のみ指定しており機体が傾いた際のモータ動作などを考慮していませんでした。
倒立動作をモジュールに優しく教える気持ちで報酬を設定したところ。。
やーーーっと傾いた方向にモータ回して力強く姿勢保持してくれるようになった!
動画はまだ外乱なしすこしづつ報酬設定の勘所がつかめてきた
子供に箸の持ち方や自転車の乗り方教える気持ちだな
エンジニア精神はむしろ邪魔になるかも#強化学習への道 pic.twitter.com/VSQQk21tOs— HomeMadeGarbage (@H0meMadeGarbage) May 10, 2025
傾いた方向にモータを回して力強く姿勢保持してくれるようになりました!
まだ外乱は印可していません。
報酬の重みなどを調整して、学習ステップを30万ほどに増やしたところ
外乱にも耐えうる学習結果を得ることができました。
外乱にも耐えうる学習結果を得られるようになった。
一旦これでSim2Realかまして実機でバックアノしてグルグル調整してく感じかなー#強化学習への道 pic.twitter.com/lLprDtx7eW
— HomeMadeGarbage (@H0meMadeGarbage) May 10, 2025
最終的な報酬は以下のとおり
1 2 3 4 5 6 |
reward = ( - 5.0 * theta**2 # 傾きペナルティ - 0.1 * omega**2 # 揺れ防止 + 5.0 * (abs(theta) < 0.005) # 直立してたらボーナス! 約0.3° - 0.5 * (np.sign(theta) != np.sign(wheel_speed)) # 傾斜とホイール回転方向が反対だとペナ ) |
倒立による報酬の傾斜を狭くしてモータ回転方向にも報酬を設けるなどして上記の倒立動作を実現させました。
Pythonコード
姿勢制御モジュールSimモデル
前回 制作したMoJuCo用モデルをそのまま流用
Fusion360で設計したSTLファイルを読み込んでいる
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 |
# mujoco_model.py def get_model_xml(): return """ <mujoco> <option timestep="0.01"/> <asset> <mesh name="case" file="assets/case.stl"/> <mesh name="motor" file="assets/motor.stl"/> <mesh name="wheel" file="assets/wheel.stl"/> </asset> <worldbody> <light name="light1" pos="1 0 3" dir="-1 0 -1" directional="true"/> <body name="case" pos="0 0 0"> <joint type="free"/> <inertial pos="0.000 0.027478 0.038948" mass="0.049217" diaginertia="3.084924e-5 4.0411796e-5 2.5326781e-5"/> <geom type="mesh" mesh="case" rgba="0.4 0.4 0.4 1"/> <body name="motor" pos="0 0 0"> <inertial mass="0.032212" diaginertia="3.289826e-6 5.548697e-6 3.290785e-6" pos="0 0.009627 0.034116"/> <geom type="mesh" mesh="motor" rgba="0.8 0.8 0.85 1"/> <body name="wheel" pos="0 0 0"> <joint name="wheel_hinge" type="hinge" axis="0 1 0" pos="0 0 0.034116" damping="0.00005"/> <inertial mass="0.036643" diaginertia="7.825643e-6 1.4733674e-5 7.825642e-6" pos="0 0.004659 0.034116"/> <geom type="mesh" mesh="wheel" rgba="0.8 0.8 0.85 1"/> </body> </body> </body> <geom type="plane" size="5 5 0.1" pos="0 0 0" rgba="0.0 0.5 0.0 1"/> </worldbody> <actuator> <motor joint="wheel_hinge" ctrlrange="-1.0 1.0" gear="0.0265"/> </actuator> </mujoco> """ |
Gymnasium環境の定義
モデルを取り込んで Gym形式で観測・行動・報酬を設定
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 |
# env_balance_guided.py import gymnasium as gym from gymnasium import spaces import numpy as np import mujoco from mujoco_model import get_model_xml class BalanceEnv(gym.Env): metadata = {"render_modes": ["human"], "render_fps": 60} def __init__(self, render_mode=None): self.model = mujoco.MjModel.from_xml_string(get_model_xml()) self.data = mujoco.MjData(self.model) self.render_mode = render_mode self.viewer = None self.observation_space = spaces.Box( low=np.array([-np.pi, -20.0, -50.0], dtype=np.float32), high=np.array([np.pi, 20.0, 50.0], dtype=np.float32), dtype=np.float32 ) self.action_space = spaces.Box( low=np.array([-1.0], dtype=np.float32), high=np.array([1.0], dtype=np.float32), dtype=np.float32 ) self.joint_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_JOINT, "wheel_hinge") self.qvel_index = self.model.jnt_dofadr[self.joint_id] self.np_random = np.random.default_rng() def quat_to_pitch(self, q): w, x, y, z = q sinp = 2.0 * (w * y - z * x) cosp = 1.0 - 2.0 * (y * y + z * z) return np.arctan2(sinp, cosp) def _get_obs(self): quat = self.data.qpos[3:7] theta_y = self.quat_to_pitch(quat) omega_y = self.data.qvel[4] wheel_speed = self.data.qvel[self.qvel_index] return np.array([theta_y, omega_y, wheel_speed], dtype=np.float32) def step(self, action): # PPOの出力([-1, 1])をスケールしてMuJoCoに渡す torque_scale = 1 # ← ここだけ調整すればOK(±3.0トルク想定) scaled_action = np.clip(action[0], -1.0, 1.0) * torque_scale self.data.ctrl[0] = float(scaled_action) mujoco.mj_step(self.model, self.data) obs = self._get_obs() theta, omega, wheel_speed = obs self.timestep_count += 1 reward = ( - 5.0 * theta**2 - 0.1 * omega**2 #- 0.001 * wheel_speed**2 #- 0.1 * (action[0]**2) # ← コレがトルク抑制項 + 5.0 * (abs(theta) < 0.005) - 0.5 * (np.sign(theta) != np.sign(wheel_speed)) # #+ 0.1 * self.timestep_count # ← ここで時間に比例して報酬を加算 ) terminated = bool(abs(theta) > np.pi / 6) # 30度以上で終了 truncated = False return obs, reward, terminated, truncated, {} def reset(self, seed=None, options=None): super().reset(seed=seed) mujoco.mj_resetData(self.model, self.data) # 位置も完全にリセット self.data.qpos[:] = 0.0 self.data.qvel[:] = 0.0 self.data.ctrl[:] = 0.0 self.timestep_count = 0 # ランダムなY軸傾き(±0.3rad) theta = self.np_random.uniform(low=-0.05, high=0.05) half_theta = theta / 2 self.data.qpos[3] = np.cos(half_theta) # w self.data.qpos[5] = np.sin(half_theta) # y # Y軸の角速度(±1.0rad/s) omega_y = self.np_random.uniform(low=-1.0, high=1.0) self.data.qvel[3] = omega_y # qvel[3] = 回転自由度Y軸(free jointの場合) mujoco.mj_forward(self.model, self.data) # 物理整合性の更新 return self._get_obs(), {} def render(self): if self.render_mode == "human": if self.viewer is None: self.viewer = mujoco.viewer.launch_passive(self.model, self.data) self.viewer.sync() def close(self): if self.viewer is not None: self.viewer.close() self.viewer = None |
Stable-Baselines3学習
強化学習アルゴリズムライブラリStable-Baselines3のPPOで強化学習
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 |
from stable_baselines3 import PPO from env_balance import BalanceEnv from stable_baselines3.common.vec_env import DummyVecEnv env = DummyVecEnv([lambda: BalanceEnv()]) model = PPO( "MlpPolicy", env, policy_kwargs={ "net_arch": [64, 64], "log_std_init": 0.3 }, learning_rate=3e-4, n_steps=2048, # ← 増やすと学習安定 batch_size=64, gamma=0.99, gae_lambda=0.95, clip_range=0.2, # ← 緩めに探索させる normalize_advantage=True, # ← Trueにすべし verbose=1 ) model.learn(total_timesteps=300000) model.save("ppo_balance") |
学習結果はppo_balance.zip で得られる。
学習結果確認
学習データで姿勢制御モジュールをMoJuCoで動作シミュレーション
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 |
# -*- coding: utf-8 -*- # run_agent.py import time import numpy as np import mujoco import mujoco.viewer from stable_baselines3 import PPO from env_balance import BalanceEnv # 環境初期化(viewer用) env = BalanceEnv(render_mode="human") # 学習済みモデル読み込み model = PPO.load("ppo_balance") # case の body ID を取得 case_body_id = mujoco.mj_name2id(env.model, mujoco.mjtObj.mjOBJ_BODY, "case") # アクションスケーリング(学習と一致させる!) torque_scale = 1 # ※train_rl.py と合わせる # 環境リセット obs, _ = env.reset() # Viewerで表示開始 with mujoco.viewer.launch_passive(env.model, env.data) as viewer: while viewer.is_running(): action, _ = model.predict(obs, deterministic=True) # --- スケーリングを追加 --- scaled_action = np.clip(action[0], -1.0, 1.0) * torque_scale env.data.ctrl[0] = float(scaled_action) # 外乱加えたいならここで env.data.xfrc_applied[case_body_id, 4] = np.random.normal(0.0, 0.01) # シミュレーション1ステップ mujoco.mj_step(env.model, env.data) # 観測更新(env.step() 呼ばずに直接処理) obs = env._get_obs() #print(f"theta={obs[0]:.3f}, omega={obs[1]:.3f}, wheel_speed={obs[2]:.3f}, action={action[0]:.3f}, torque={scaled_action:.3f}") viewer.sync() time.sleep(env.model.opt.timestep) # 90度以上で倒れたらリセット theta = obs[0] if abs(theta) > np.pi / 2: obs, _ = env.reset() |
おわりに
ついに強化学習に挑戦して、姿勢制御モジュールの倒立動作を実現することができました。
次はSim2Realで実機にフィードバックさせて強化学習の恩恵を感じたいと思います。
おそらくSimと実機の違いでかなり苦しむと思いますし、現時点ではどうやって実機に落とし込むのかもわかっていません。
さて次はどうなっているのか。
新しいことを詰め込み過ぎて頭が割れそうですが頑張ります。