ABEJA Tech Blog

中の人の興味のある情報を発信していきます

2足歩行ロボットを作ってみよう(前編)

はじめに

こんにちは、ABEJAのラボで研究開発をしている藤本です。この記事はABEJAアドベントカレンダー2025の25日目の記事です。

近年、フィジカル AI の盛り上がりとともに、ロボティクス分野への注目も高まっています。ABEJA のブログでもロボット関連の記事が増えてきました。さまざまなロボットが開発されていますが、僕個人としては特にヒューマノイドに強い興味があります。

現在は技術的・環境的ハードルから、車輪ベースなど歩行以外の機構が主流ですが、最終的には汎用性の高いヒューマノイドに向かうだろうと考えています。展示会に足を運ぶと多くの企業がヒューマノイドを展示していますが、フルスクラッチで開発している例は意外と少ないと感じます。

「それなら自分で作ってみよう!」ということで、二足歩行ロボットの開発に挑戦してみました。機体の制作、シミュレーション、実機への転移(Sim2Real)などやることは盛りだくさんです。今回の記事では前編ということでシミュレーションまでの流れを紹介します。二足歩行の制御の方法としてはMPCを使う方法など様々ありますが、柔軟な動作を獲得しやすくできると良いので強化学習でやってみましょう。

ロボットの制作

ハードウェアの設計

まずはロボットの基本構成を考えます。今回は財布の事情もあり、シンプルに足の関節を3つに限定し、姿勢の認識もIMUのみとします。アクチュエータとしては Dynamixelのモーターを採用しました。Dynamixelのモーターはポジション制御・速度制御・トルク制御など複数の制御方式を持っており、ROSとの連携やPythonのSDKもあるので便利そうです。以下のモーターを購入してみました。

  • XC-330-M181T × 2
  • XL-330-M288-T × 4

制御のボードとしてOpenRB-150を、姿勢推定IMUとしてWitMotion WT901Bを使います。

モデルの作成

次にロボットのモデルを作っていきましょう。CADでロボットの機体を設計してURDFに変換します。作成したURDFは以下のようなモデルとなります。

それっぽいのが出来たので、各パーツを3Dプリンタで印刷して組み立ててみました。

組み立てたロボットは以下になります。実物があると、やっぱりテンションは上がりますね。

シミュレーション

USDの作成とIsaacSimでの確認

作成したロボットモデルのURDFからIsaacLabでシミュレーションをしていきましょう。まずは、URDFファイルをIsaacLabで読み込めるようにUSDに変換します。

/isaaclab.sh -p scripts/tools/convert_urdf.py \
        PATH_TO_URDF PATH_TO_USD \
        --joint-target-type position \
        --headless

変換したファイルをIsaacSimで確認してみましょう。IsaacSimのメニューからCreate-> Physics->Ground Planeを選択、z軸の位置を調整して大まかにロボットの高さを確認できるのでメモをしておき、後ほどロボットをスポーンさせる際のz座標の設定で使います。今回は0.189くらいですね。

プロジェクトの作成

IsaacLabでプロジェクトを作っていきます。以下のコマンドで対話的にプロジェクトを作れます。プロジェクトをIsaacLabディレクトリ内に直接作るか外部に作るか、環境について、学習フレームワークについて聞かれます。ここでは、external、single agent、rsl_rlを選択します。

./isaaclab.sh --new

プロジェクトを作ったら、ソースのあるディレクトリに移動してプロジェクトをインストールします。

$ cd [PROJECT_NAME]/source/[PROJECT_NAME]
pip install -e .

プロジェクトの構成は初期は以下のようになります。各ファイルについて簡単に説明しましょう。scriptsディレクトリは、学習や推論などの様々なスクリプトが含まれます。基本的には触る必要はありません。sourceディレクトリ以下に、学習のための様々なスクリプトが含まれます。基本的に触るのはmanager_basedディレクトリ以下の[PROJECT_NAME]_env_cfg.py(環境設定)とrsl_rl_ppo_cfg.py(学習設定)の2つになります。初期状態はcartpoleのスクリプトが入っているので、後ほどこれを修正していきましょう。

.
├── README.md
├── scripts
│   ├── list_envs.py
│   ├── random_agent.py
│   ├── rsl_rl
│   │   ├── cli_args.py
│   │   ├── play.py
│   │   └── train.py
│   └── zero_agent.py
└── source
    └── [PROJECT_NAME]
        ├── config
        │   └── extension.toml
        ├── docs
        │   └── CHANGELOG.rst
        ├── pyproject.toml
        ├── setup.py
        └── [PROJECT_NAME]
            ├── __init__.py
            ├── tasks
            │   ├── __init__.py
            │   └── manager_based
            │       ├── __init__.py
            │       └── [PROJECT_NAME]
            │           ├── __init__.py
            │           ├── agents
            │           │   ├── __init__.py
            │           │   └── rsl_rl_ppo_cfg.py
            │           ├── mdp
            │           │   ├── __init__.py
            │           │   └── rewards.py
            │           └── [PROJECT_NAME]_env_cfg.py
            └── ui_extension_example.py

学習条件の設定

IsaacLabでは、rsl_rlを用いて強化学習をする際には環境設定(env)と 学習設定(agent)について設定を行います。独自の観測・報酬関数・終了判定関数を使う時は、mdpディレクトリ下にスクリプトをします。それ以外はパラメータの設定のみで動きます。環境側ではロボットモデル、地形、観測、報酬、シミュレーション設定などを扱い、学習側では学習手法・ネットワーク構造・ハイパーパラメータを設定します。

環境の設定

まずロボットの設定から始めていきます。ロボットの設定は[PATH_TO_ROBOT].pyに記述します。IsaacLabのisaaclab_assetsのディレクトリに沢山のアセットがあるので、それを参考にします。ここではhumanoid.pyunitree.py中のG1のアセットを参考にしました。ロボットの全体の設定はArticulationCfg というクラスに記述していきます。usd_pathに先程のUSDファイルのパスを指定します。posにロボットの位置を、init_stateに各ジョイントの初期値を入れます。先程メモしておいた高さをここで設定します。重要な設定の一つにactuatorsの設定があります。actuatorsではアクチュエータのタイプを設定に応じてクラスを選び、クラス内で以下のパラメータを設定します。タイプとしては、例えばImplicitActuatorやDCMotorsなどがあり、指定した制御値に対してどのような挙動をシミュレーションに含めるかの違いがあります。パラメータとしては、上2つはモーターの仕様から数値を入れ、下2つはPD制御のパラメータです。制御パラメータの数値はよくわからないので、現時点では一旦は適当に設定しましょう。

項目 概要
effort_limit 最大トルク上限
velocity_limit 最大角速度上限
stiffness 仮想バネの強さ
damping 減衰(動きを抑える力)

次は環境の設定に移りましょう。設定するのはInteractiveSceneCfg、ActionsCfg、ObservationsCfg、EventCfg、RewardsCfg、TerminationsCfgです。設定すべき項目が多すぎるので、ここではIsaacLabのコード中にあるclassic/humanoidというアセットの設定をコピーして利用することとました。

ActionsCfgで、アクチュエータにどのタイプの指令を送るかを設定します。トルク制御の場合はJointEffortActionCfg、ポジション制御の場合はJointPositionActionCfgを利用します。今回はトルク制御を想定してJointEffortActionCfgを利用します。

観測の情報は、ObservationsCfgに設定します。humanoidをベースにしつつノイズを与えて以下の観測を採用しました。

項目 説明
base_height ロボット本体(ベースリンク)の地面からの高さ
base_lin_vel ロボットベースの並進速度(x, y, z 方向)
base_ang_vel ロボットベースの角速度(roll, pitch, yaw の回転速度)
base_yaw_roll ベースリンクの yaw(向き)と roll(左右の傾き)
base_angle_to_target ロボットの前方方向とゴール方向の角度差(ターゲットへの向き誤差)
base_up_proj ロボットの「上向きベクトル」がワールドの上方向(Z軸)とどれだけ一致しているか(姿勢の直立度)
base_heading_proj ロボットの前方向ベクトルがゴール方向とどれだけ一致しているか(方向一致度)
joint_pos_norm 各関節角度を正規化した値(関節位置)
joint_vel_rel 各関節の速度(関節角速度、もしくは速度指令との相対値)
feet_body_forces 足リンクに伝わる外力(接触力や関節からの力などの 6D wrench)
actions 前ステップで実行したアクション(関節コマンド)

EventCfgでは、ロボットの各種イベントを設定します。以下を利用することにしました。

項目 説明
physics_material ロボットや地面の摩擦係数・反発係数など、物理シミュレーションの材質パラメータをランダム化する設定
add_base_mass ロボット本体(ベース)の質量をランダムに変化させることで、重さの違いに対するロバスト性を上げる設定
reset_base エピソード開始時のロボットベースの位置・姿勢をランダム化する初期化設定
reset_robot_joints ロボットの関節角度や関節速度をリセットするときにランダム化する初期姿勢設定
push_robot 学習中にランダムな外力をロボットへ与え、外乱に対して安定に動けるようにするためのランダム押し設定

報酬はRewardsCfgに設定します。ここが一番大変です。実験では色々試しましたが最終的に採用した報酬を以下に記載します。この他に実装した報酬関数は別に記載します。

項目 説明
progress ゴール方向にどれだけ前進したか(タスクの進捗に応じた報酬)
alive エピソードが終了せず、ロボットが倒れずに生存している時間に対する報酬
upright ロボットが垂直に立っており、姿勢が安定している度合い
move_to_target ロボットの前方方向がゴール方向と一致し、その方向へ移動できているか
lin_vel_z_l2 垂直方向(Z)の速度の変化量を罰する項(上下にバタつかないようにする)
ang_vel_xy_l2 水平方向(X-Y)周りの角速度を罰する項(ピッチ・ロールの急変を抑える)
action_l2 行動(アクション)値の L2 ノルム。過大な関節速度指令を抑えるためのペナルティ
flat_orientation_l2 ロボットが水平姿勢から大きく傾いていないか(安定した姿勢維持)
dof_torques_l2 各関節にかかったトルクの大きさを罰する項(無駄な力を抑える)
dof_acc_l2 関節角加速度の大きさを罰する項(急激な動作を抑えて滑らかにする)
reference_height ロボットが目標とする基準高さ(センターの高さ)を維持できているか
feet_air_time_positive_biped 二足歩行時に、左右の足が適切な「空中時間」を持ち、歩行リズムが自然かどうか
feet_slide 接地中の足が横滑りしていないか(滑りをペナルティ)
termination_penalty 転倒・危険姿勢・ゴールから離れすぎなどでエピソードが途中終了したときのペナルティ

終了条件はTerminationsCfgで以下のようにしています。

項目 説明
time_out 1エピソードの最大ステップ数(または最大時間)を超えた場合に終了する
torso_height ロボットの本体(胴体)の高さがしきい値より低くなった場合に終了する(転倒などの判定)

Agentの設定

強化学習について

IsaacLabでは、rl_games、rsl_rl、skrlなどの強化学習ライブラリをバックエンドとして利用できます。今回は標準的な強化学習手法の一つであるPPOを利用します。PPOとは、エージェントが行動方針(方策)を更新する際に、現在の方策と更新前の方策の確率比が大きく変わりすぎないよう更新量をクリップして調整しつつ、報酬が高くなる方向へ少しずつ安全に改善していく強化学習アルゴリズムです。その制御によって学習が不安定になりにくく、効率よく方策を最適化できることが特徴です。

設定の詳細

強化学習に関する設定項目は以下です。

項目 概要 設定値
num_steps_per_env 1エピソードあたり環境から収集するステップ数 24
clip_actions アクションのクリッピング上限(制御指令の暴走防止) 10.0
init_noise_std アクション出力に付与する初期ノイズの標準偏差(探索用) 1.0
actor_obs_normalization Actor に入力する観測を正規化するか true
critic_obs_normalization Critic に入力する観測を正規化するか true
actor_hidden_dims Actor ネットワークの隠れ層(ユニット数) 128 / 128 / 128
critic_hidden_dims Critic ネットワークの隠れ層(ユニット数) 128 / 128 / 128
activation ネットワークで使用する活性化関数 elu
class_name 使用アルゴリズム PPO
num_learning_epochs 1回の更新で学習するエポック数 5
num_mini_batches ミニバッチ分割数(学習安定性向上) 4
learning_rate 学習率 0.0003
gamma 割引率(将来報酬の重みづけ) 0.99
lam GAE λ(Advantage の平滑性調整) 0.95
entropy_coef エントロピー係数(探索促進) 0.02
desired_kl KLダイバージェンスの目標値(過学習防止) 0.01
max_grad_norm 勾配クリッピングの最大ノルム 1.0
value_loss_coef Value loss の重み 1.0
clip_param PPOのクリップ係数(Policy更新の安定化) 0.2

タスクの設定

IsaacLabでは、実行に関する設定をタスクとして登録します。__init__.pyに以下のようにしてタスクを登録してやります。Template-[PROJECT_NAME]-Rl-v0という名前のタスクを登録し、envはenv_cfg_entry_pointに指定のクラス、agent(学習)はrsl_rl_cfg_entry_pointに示したクラスの設定が読み込まれます。

gym.register(
    id="Template-MyProject-Rl-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.[PROJECT_NAME]_env_cfg:MyRlEnvCfg",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:MyPPORunnerCfg",
    },
)

ここまでのセッティングで学習をすると、以下のように大量のシミュレーションを並列に動かすことが出来ます。

歩容改善の取り組みについて

左右対称の歩容を学習してもらえるのが理想ですが、報酬の設計・カリキュラムの設計が甘いと、思ったような動作をしてくれません。例えば、スキップしたり、飛び跳ねたり、左右非対称になってしまったり。ここでは、歩容改善の色んな取り組みについて紹介します。作業時間が十分取れなかったので、どれがどのくらい聞いたかは調査できませんでした・・・。

対称性の学習

ロボットの安定な姿勢の一つとして、片足を前に出して、もう片足を後ろにし、すり足で進むというものがあります。報酬ですり足に対するペナルティを設定していたとしても、安定して進める報酬が勝ってしまい、左右非対称な歩行になってしまうことがしばしばあります。

これに対して、左右対称のデータ拡張やロスに関する手法があります。Learning Symmetric and Low-energy Locomotionという論文では、rsl_rlのフレームワークでは対称性を扱うことができるので、実装してみました。具体的には、観測と行動を左右対称に変換する関数をそれぞれ用意して設定します。ちなみにsymmetric lossを入れると学習中に崩壊することが多く、augmentationのみ利用するのが良さそうでした。

学習パラメータの改善

PPOでは学習をしていると途中でモデルが崩壊することがあります。一度崩壊するとそこに安定してしまい、抜け出せなくなってしまいます。これに対し、Mitigating Policy Collapse in Deep Reinforcement Learning では、学習率のベータを調整することで改善する手法を提案しました。具体的には、Adamにおけるbeta1とbeta2を同じ数値にすることで崩壊が減るようです。実装が簡単なので入れていますが、効果はよくわからなかったです。

周期性の導入

人間が歩くときは、リズムよく左右の足を交互にステップを踏みます。ロボットにもそのような周期性の導入をするという研究があります。具体的には、Learning 3D Bipedal Walking with Planned Footsteps and Fourier Series Periodic Gait Planningにおいては、観測に周期情報(sin(t)とcos(t))を与え、報酬側で現在の周期に対応して足踏みが出来ているかどうかをチェックします。

ポテンシャルベースでの報酬

Benchmarking Potential Based Reward Shaping for Humanoid Locomotion では、報酬を設計する際に、直接報酬ではなく、状態間の「遷移」に焦点を当て、ある状態から次の状態へ移動した際のポテンシャル関数の差分(変化量)を報酬とすることで、パラメータの変化に対してロバストになる。

様々な報酬について

論文の工夫を入れたら正しく動くというわけでもなく、色んな報酬を実装して試してみました。それぞれどのくらい効いたかもまとめたかったのですが、時間も無かったので、良い感じに動くまで試行錯誤していました。ちなみに結果としては、報酬を入れると、報酬に応じて動いてくれるものの、どうしても不自然な動きになってしまうことがわかりました。以下は今回の実験の中で実装した関数群です。沢山実装したなぁ。

歩容・接地パターン系

左右交互に歩けるような報酬を色々考えてみました。

項目名 概要
alternating_gait_reward 左右交互の接地パターンができているかを評価。両足接地/両足浮遊をペナルティ。
single_foot_contact_reward 片足のみ接地(single support)を理想とし、それ以外をゼロ報酬。
jump_penalty 両足が空中にある=ジャンプ状態ならペナルティ。
split_stance_penalty 両足接地時に X 方向で過度に離れているとペナルティ。
lead_leg_switch_reward 左右のリードレッグ(前に出ている方)が適切に交互に切り替わると報酬。
feet_x_range_utilization_reward 両足が近すぎるとペナルティ、適度な左右差があると報酬。
feet_x_range_penalty 各足の X 位置が正常範囲(参照軌跡)から逸脱するとペナルティ。
stand_fix_pos 左右足の X 位置差が小さすぎるとペナルティ。
gait_phase_reward 位相に応じ、スイング中の接地/スタンス中の足移動をペナルティ。

足の軌道・ストライド・空中時間系

歩容と似ていますが、歩容ほど制約の強くない、足の軌跡に関する報酬も色々作ってみました。

項目名 概要
foot_slip_penalty 接地中の足が滑る(速度が閾値以上)とペナルティ。
foot_height_reward スイング中の足が十分に持ち上がっていれば報酬。
feet_air_time 足の空中時間が閾値より長いと評価。
feet_air_time_positive_biped 片足支持時間・空中時間を正方向に報酬化(2足歩行専用)。
feet_slide 接地足の滑り速度が大きいとペナルティ。
foot_stride_reward 離陸〜着地までのストライド距離(XY距離)に応じて報酬。
alternating_step_forward_reward / v2 スイング中の足が前進すれば報酬、より良いバージョン。
alternating_step_speed_reward スイング中の足速度がベースより前向きで速いと報酬。
feet_average_x_position_reward 両足の平均 X 位置が目標値に近いと報酬。

姿勢・位置・速度の追従/安定化系

姿勢の安定性に関する様々な報酬です。足先ではなく体の状態に関する報酬ですね。

項目名 概要
target_speed_tracking_reward 目標速度へ近づけば報酬、離れれば負。
reference_height_reward ロボット高さが参照平均に近いほど高報酬。
velocity_jerk_penalty 前フレームとの速度差が大きい(ガタつき)とペナルティ。
torso_forward_lean_reward torso の pitch が目標前傾角に近いほど報酬。

ジョイント・動力学系(ペナルティ)

項目名 概要
joint_pos_limits_penalty_ratio ジョイント角度が制限に近づくほどペナルティ、ギア比で重み付け。
power_consumption 関節トルク×速度で消費パワーを計算、総量ペナルティ。

模倣学習(Imitation Learning)

別の機体パラメータを使うことで、実機とは異なる状況でありつつ上手く学習をさせたモデルが出来上がったので、足の軌跡を模倣するのもやってみました。

項目名 概要
link_position_imitation_reward 全リンク位置を参照軌跡と比較し、誤差が小さいほど報酬。
link_relative_position_imitation_reward base_link基準の相対リンク位置を模倣する報酬。
joint_angle_imitation_reward 関節角度を参照軌跡に合わせる報酬。
x_direction_imitation_reward X方向(進行方向)の相対位置のみ模倣する報酬。

蒸留

先程の観測データには、ロボットに搭載していないセンサデータなどが含まれます。例えば目標値との相対距離などは、ロボットが自己位置推定をしないと取ることができません。そういった本来計測できない特殊な情報を特権情報と呼びます。一方、そのような特権情報がなくても動作させたくなります。そこで、特権情報ありで推論したモデルの出力を、ロボットが計測可能な観測データに転移する蒸留をやっていきましょう。

蒸留は、IsaacLabでは環境側の設定として、特権情報をなくした生徒用の観測を設定します。Agentクラスとして、RslRlDistillationRunnerCfgクラスを利用します。ObservationsCfgの中に、StudentCfgというのを作り特権情報を廃した設定をしてあげます。IMUのみで計測できそうな以下の観測を残すことにしました。

項目 説明
base_ang_vel ロボットベースの角速度(roll, pitch, yaw の回転速度)
base_yaw_roll ベースリンクの yaw(向き)と roll(左右の傾き)
joint_pos_norm 各関節角度を正規化した値(関節位置)
joint_vel_rel 各関節の速度(関節角速度、もしくは速度指令との相対値)
actions 前ステップで実行したアクション(関節コマンド)

Agent側ではRslRlDistillationRunnerCfgを継承したクラスに、各種パラメータを設定します。obs_groupsを以下のように設定することで、教師と生徒の観測を指定できます。

obs_groups = {
    "policy": ["student"], 
    "teacher": ["policy"]
}

また、__init__.pyにタスクを追加してあげましょう。蒸留は、歩行自体の安定性は落ちるものの、学習自体は比較的安定進むようですね。

gym.register(
    id="Template-MyProject-Rl-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.[PROJECT_NAME]_env_cfg:MyRlEnvCfg",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:MyPPORunnerCfg",
        "rsl_rl_distillation_cfg_entry_point": f"{agents.__name__}.rsl_rl_distillation_cfg:MyDistillationRunnerCfg",
    },
)

学習と推論

学習は以下のように行います。学習ログをwandbに管理することも可能です。

python scripts/rsl_rl/train.py \
        --task=Template-[PROJECT_NAME]-Rl-v0 \
        --max_iterations=10000
       --headless --logger wandb

学習したモデルの再生は以下のように行います。

python scripts/rsl_rl/play.py --task=Template-[PROJECT_NAME]-Rl-v0

蒸留についても同様に以下のように学習・再生を行います。

# 学習
python scripts/rsl_rl/train.py \
    --task Template-[PROJECT_NAME]-Rl-v0 \
    --agent rsl_rl_distillation_cfg_entry_point \
    --load_run 2025-12-19_00-52-52 \
    --checkpoint model_ \
    --headless \
    --logger wandb

# 再生
python scripts/rsl_rl/play.py \
    --task Template-[PROJECT_NAME]-Rl-v0 \
    --checkpoint logs/rsl_rl/[PROJEC_NAME]/2025-12-20_00-27-36_distillation/model_29999.pt \
    --agent rsl_rl_distillation_cfg_entry_point

実験

では、実際に学習と推論をやっていきましょう。実験では、強化学習および蒸留、それぞれについての推論結果について以下に示します。

学習結果

強化学習の報酬ログ

以下の図のように報酬が順調に伸びることを確認できています。

とはいえ、単に報酬が伸びるだけでは上手く行っているとは言えず、歩容に関する報酬などもチェックして、正しく歩けているかをチェックする必要があります。例えば以下の例では、報酬は伸びているが交互の歩容の報酬は低いという状況になっています。交互の歩容の重みが低すぎて、前に行くことを優先してしまった結果として以下のような状況が発生します。とはいえ、単純に歩容のペナルティを大きくしすぎると、今度は良い歩き方を見つけてくれず学習が進まないという状況になったりもします。歩容など正解を見つけるのが難しい報酬値が上がるように、上手く機体を設計する・カリキュラムを設計する・中間報酬を入れるなどが必要になり、強化学習はなかなか大変ですね。

さて、色々調整をした結果として、ある程度良い感じに報酬が得られたモデルの再生結果は以下のようになりました。ノイズを多く入れている・ロボットを軽く押すなどもしながら、ある程度ふらつきながらも歩けていることが確認できます。ちょっと頼りないので、年末年始に時間を取ってもう少し改善したいですね。

蒸留の報酬のログ

続いて蒸留をやっていきましょう。強化学習フェーズで学習できれば蒸留は結構安定するようですね。報酬は多少下がるものの安定して学習できました。

再生結果は以下になります。強化学習の結果と概ね一致する動作を学習できていますね。

余談

ここまで行くの大変でした。モーターを発注したくとも品切れしていたり、URDFの設定を間違えてロボットの重さが10倍になっていたり、URDF側で関節の制限を記述してもモデルはその制限を突破して推論してくるからハード側で制限をつける必要があり機体の再設計をしたりなど大変すぎた。

実機でもお試し実験

せっかくなので、大急ぎで今のセッティングでSim2Realチャレンジまでやってみましょう、超突貫で実装だ!IMUをロボットに取り付ける治具をCADで作り3Dプリンタで印刷して本体にネジ止めてIMUの通信とモータの通信をOpenRBで一括してやろうと思ったけど両方同時に扱えなかったので、取り急ぎIMUはArudino経由で通信することにし、IMUのデータ取得スレッド、ジョイントデータ取得スレッド、ジョイント送信スレッドをそれぞれ立ち上げ、取得スレッドではなるべく速い周期でデータを収集、送信スレッドではシミュレータと同じ40ms程度でトルク送信し、座標系と各観測のスケール、ネットワークの出力からトルク値への変換式はよくわからないけど勘で大急ぎで実装・・・締め切りギリギリで間に合った!?・・・よし行くぞ・・・!

・・・\(^o^)/

次回に向けて

さて、今回は直接トルク制御を学習して機体を動かそうとしていますが、実際のロボットを想定する場合は、一度ポジション制御で学習してから、ポジションをトルクに変換するActuatorNetを学習してSim2Realをやったりする方がよりロバストとのことです。Learning agile and dynamic motor skills for legged robotsにあるように、ロボットをランダムに動かして(今回であれば屈伸運動など)モーターの特性のデータを取っておき、トルクを出力するモデルを学習します。トルクのシミュレーションは非常に難しいため、このようなアプローチを取ることでロバストに出来ます。IsaacLabsのサンプルでもその様になっているようですね。ということで、次回はActuatorNetの学習を行い、トルク制御でロボットの2足歩行をやって行こうと思います。後半へ続く。良いお年を。

We Are Hiring!

ABEJAは、テクノロジーの社会実装に取り組んでいます。 技術はもちろん、技術をどのようにして社会やビジネスに組み込んでいくかを考えるのが好きな方は、下記採用ページからエントリーください! (新卒の方やインターンシップのエントリーもお待ちしております!) careers.abejainc.com

特に下記ポジションの募集を強化しています!ぜひ御覧ください!

トランスフォーメーション領域:データサイエンティスト

トランスフォーメーション領域:データサイエンティスト(ミドル)

トランスフォーメーション領域:データサイエンティスト(シニア)