Isaac Simを使ってUnitree G1の5本指ハンドのデモをシミュレートし、実機にデプロイする

Isaac Simを使ってUnitree G1の5本指ハンドのデモをシミュレートし、実機にデプロイする

2026.04.13

はじめに

前回の記事ではIsaac Sim上でDex3ハンド(3本指)をDDS経由で動かしました。本記事では、Inspire Robots製の5本指ハンドRH56DFQ(RH56DFXのUnitree向けカスタムモデル)をIsaac Simで動かし、さらに実機のG1にデプロイするところまでをやってみます。

デモとして「5本指のカウントダウン(5→4→3→2→1→0)」を実装します。親指から順に折りたたんでいき、最後にグーで締めるという動きです。

前回の記事
https://dev.classmethod.jp/articles/unitree-g1-dex3-hand-isaac-sim/

RH56DFQとDex3の違い

RH56DFQはDex3とは異なるデータ構造と通信トピックを使用します。

Dex3 RH56DFQ
指の数 3本(親指・人差し指・中指) 5本
片手DoF 7 6
データ型 HandCmd_(unitree_hg) MotorCmds_(unitree_go)
DDSトピック rt/dex3/right/cmd, rt/dex3/left/cmd rt/inspire/cmd(左右まとめて1トピック)
DDSフラグ --enable_dex3_dds --enable_inspire_dds
有効パラメータ q, kp, kd qのみ(他は予約)

RH56DFQの最も大きな特徴は、左右の手を1つのトピック(rt/inspire/cmd)で一括制御する点です。MotorCmds_の配列インデックス0〜5が右手、6〜11が左手に対応します。

RH56DFQの関節マッピング

dfx_inspire_serviceのREADMEに公式のマッピングが記載されています。

Id 0 1 2 3 4 5 6 7 8 9 10 11
Hand 右手 左手
Joint pinky ring middle index thumb-bend thumb-rotation pinky ring middle index thumb-bend thumb-rotation

各指は1モーター(開閉のみ)で制御し、親指だけ2モーター(曲げ+回転)を持ちます。シミュレータと実機の両方で動作確認した結果、Dex3のように左右で関節の符号が異なるという問題は見られず、シンプルにqの値だけで制御できました。

MotorCmds_の構造

RH56DFQの制御に使うデータ型はMotorCmds_MotorCmd_です。Dex3のHandCmd_とは異なるIDL定義を使います。

MotorCmd_のフィールドを確認したところ、以下のシグネチャでした。

(mode: uint8, q: float32, dq: float32, tau: float32, kp: float32, kd: float32, reserve: array[uint32, 3])

ポイントはreserveフィールドです。Dex3のMotorCmd_ではreserveはintでしたが、RH56DFQのMotorCmd_(unitree_go)では uint32の配列(長さ3) です。reserve=0とするとシリアライズエラーになるため、reserve=[0, 0, 0]と指定する必要があります。

# NG: reserveがintだとエラー
MotorCmd_(mode=1, q=0.5, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=0)

# OK: reserveは配列で指定
MotorCmd_(mode=1, q=0.5, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=[0, 0, 0])

また、MotorCmds_のインスタンスはデフォルトコンストラクタで生成してからcmdsフィールドにリストを代入します。

cmd = MotorCmds_()
cmd.cmds = motors  # MotorCmd_のリスト

開閉の値

実際にシミュレータ上でさまざまな値を送って確認したところ、RH56DFQでは以下の対応でした。

  • オープン(開く): q = 1.0
  • クローズ(閉じる): q = 0.0

RH56DFQは0が閉じた状態、1が開いた状態に対応します。

シミュレーションの起動

conda activate unitree_sim_env
cd ~/unitree_sim_isaaclab
python sim_main.py --device cpu --enable_cameras --task Isaac-PickPlace-RedBlock-G129-Inspire-Joint --enable_inspire_dds --robot_type g129

Dex3のときと同様に、--enable_inspire_ddsフラグを付けないとハンドは表示されますが外部から操作できません。

動作テスト

まず全指のオープン/クローズが動くか確認するテストスクリプトです。

cat << 'ENDOFFILE' > ~/unitree_sim_isaaclab/inspire_test.py
import time
from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize
from unitree_sdk2py.idl.unitree_go.msg.dds_ import MotorCmds_, MotorCmd_

ChannelFactoryInitialize(1)

pub = ChannelPublisher("rt/inspire/cmd", MotorCmds_)
pub.Init()
time.sleep(1)

def make_cmd(positions):
    motors = []
    for q in positions:
        motors.append(MotorCmd_(mode=1, q=q, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=[0, 0, 0]))
    cmd = MotorCmds_()
    cmd.cmds = motors
    return cmd

O = 1.0  # open
C = 0.0  # close

print("=== Inspire Hand test ===")
print("Ctrl+C to stop\n")

try:
    cycle = 0
    while True:
        cycle += 1
        print(f"[{cycle}] OPEN")
        cmd = make_cmd([O] * 12)
        for _ in range(50):
            pub.Write(cmd)
            time.sleep(0.02)
        time.sleep(1)
        print(f"[{cycle}] CLOSE")
        cmd = make_cmd([C] * 12)
        for _ in range(50):
            pub.Write(cmd)
            time.sleep(0.02)
        time.sleep(1)
except KeyboardInterrupt:
    print("\ndone")
ENDOFFILE
conda activate unitree_sim_env
cd ~/unitree_sim_isaaclab
python inspire_test.py

両手が同時にオープン/クローズを繰り返せば成功です。
https://youtu.be/qYq1B8iTDiM?si=ifEd3SVCCpd2bak2

カウントダウンの実装

5→4→3→2→1→0と親指から順に折りたたんでいくカウントダウンを実装します。

cat << 'ENDOFFILE' > ~/unitree_sim_isaaclab/inspire_countdown.py
import time
from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize
from unitree_sdk2py.idl.unitree_go.msg.dds_ import MotorCmds_, MotorCmd_

ChannelFactoryInitialize(1)

pub = ChannelPublisher("rt/inspire/cmd", MotorCmds_)
pub.Init()
time.sleep(1)

O = 1.0  # open
C = 0.0  # close

def make_cmd(positions):
    motors = []
    for q in positions:
        motors.append(MotorCmd_(mode=1, q=q, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=[0, 0, 0]))
    cmd = MotorCmds_()
    cmd.cmds = motors
    return cmd

def both_hands(pinky, ring, middle, index, thumb_bend, thumb_rot):
    """両手同じポーズ。片手=[pinky, ring, middle, index, thumb_bend, thumb_rot]"""
    h = [pinky, ring, middle, index, thumb_bend, thumb_rot]
    return h + h

# 5から親指→人差し指→中指→薬指→小指の順に折る
poses = [
    ("5 - all open",              both_hands(O, O, O, O, O, O)),
    ("4 - thumb folded",          both_hands(O, O, O, O, C, C)),
    ("3 - thumb+index folded",    both_hands(O, O, O, C, C, C)),
    ("2 - thumb+index+mid folded", both_hands(O, O, C, C, C, C)),
    ("1 - only pinky open",       both_hands(O, C, C, C, C, C)),
    ("0 - fist",                  both_hands(C, C, C, C, C, C)),
]

def send_pose(positions, duration=2.0):
    cmd = make_cmd(positions)
    steps = int(duration / 0.02)
    for _ in range(steps):
        pub.Write(cmd)
        time.sleep(0.02)

print("=== Inspire Hand Countdown ===")
print("Starting in 3 sec...\n")
time.sleep(3)

for label, pos in poses:
    print(f"  {label}")
    send_pose(pos, duration=2.0)
    time.sleep(0.5)

print("\nReturning to open...")
send_pose(poses[0][1], duration=2.0)
print("Done")
ENDOFFILE
conda activate unitree_sim_env
cd ~/unitree_sim_isaaclab
python inspire_countdown.py

https://youtu.be/AjRv-aiOM1c?si=kaL6QRdN3EdXEnjr

腕の制御を追加する

カウントダウンを見せるために、腕を上げて手のひらを正面に向けるポーズにします。

G1の腕はシミュレータ上ではrt/lowcmdLowCmd_を送ることで制御できます。CRC検証が必要です。

G1 29DoFのアーム関節構成は以下の通りです。

インデックス 関節名 説明
15 LeftShoulderPitch 左肩の前後
16 LeftShoulderRoll 左肩の横開き
17 LeftShoulderYaw 左上腕のねじり
18 LeftElbow 左肘
19 LeftWristRoll 左手首のねじり
20 LeftWristPitch 左手首の上下
21 LeftWristYaw 左手首の左右
22-28 Right* 右腕(同構成)

手のひらを正面に向けて前腕を立てるポーズに調整した結果、以下のターゲット値になりました。

ARM_TARGET = [
    -0.5, 0.0, 0.0, -1.4, 1.57, 0.0, 0.0,   # left arm
    -0.5, 0.0, 0.0, -1.4, -1.57, 0.0, 0.0,   # right arm
]
  • ShoulderPitch = -0.5: 腕を前方に上げる
  • Elbow = -1.4: 肘を曲げて前腕を立てる(正の値だと逆に伸ばす方向になる)
  • WristRoll = ±1.57(π/2): 手のひらを正面に向ける(左右で逆回転)

なお、Wholebodyタスクで立った状態で腕を上げるとバランスを崩して倒れてしまうため、シミュレータではJointタスク(座った状態)で動作確認を行い、立った状態での動作は実機で行う方針としました。

腕の制御+カウントダウンを統合したスクリプト(inspire_full_demo.py)は以下の通りです。

処理フロー:

  1. rt/lowstateをsubscribeして現在の関節角度を取得
  2. rt/lowcmdLowCmd_+CRCを送り、腕をターゲットポーズまで補間移動(3秒)
  3. 腕を維持しながらrt/inspire/cmdでカウントダウンを実行
  4. カウントダウン終了後、腕を元のポーズに戻す
cat << 'ENDOFFILE' > ~/unitree_sim_isaaclab/inspire_full_demo.py
import time
import sys
import numpy as np

from unitree_sdk2py.core.channel import ChannelPublisher, ChannelSubscriber, ChannelFactoryInitialize
from unitree_sdk2py.idl.default import unitree_hg_msg_dds__LowCmd_
from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowCmd_, LowState_
from unitree_sdk2py.idl.unitree_go.msg.dds_ import MotorCmds_, MotorCmd_
from unitree_sdk2py.utils.crc import CRC

# === G1 Joint Index (29DoF) ===
class J:
    LeftShoulderPitch = 15
    LeftShoulderRoll = 16
    LeftShoulderYaw = 17
    LeftElbow = 18
    LeftWristRoll = 19
    LeftWristPitch = 20
    LeftWristYaw = 21
    RightShoulderPitch = 22
    RightShoulderRoll = 23
    RightShoulderYaw = 24
    RightElbow = 25
    RightWristRoll = 26
    RightWristPitch = 27
    RightWristYaw = 28

ARM_JOINTS = [
    J.LeftShoulderPitch, J.LeftShoulderRoll, J.LeftShoulderYaw, J.LeftElbow,
    J.LeftWristRoll, J.LeftWristPitch, J.LeftWristYaw,
    J.RightShoulderPitch, J.RightShoulderRoll, J.RightShoulderYaw, J.RightElbow,
    J.RightWristRoll, J.RightWristPitch, J.RightWristYaw,
]

# 手のひらを正面に向けて前腕を立てるポーズ
ARM_TARGET = [
    -0.5, 0.0, 0.0, -1.4, 1.57, 0.0, 0.0,   # left arm
    -0.5, 0.0, 0.0, -1.4, -1.57, 0.0, 0.0,   # right arm
]

# === Global state ===
low_state = None

def on_low_state(msg):
    global low_state
    low_state = msg

# === Inspire Hand helpers ===
O = 1.0  # open
C = 0.0  # close

def make_inspire_cmd(positions):
    motors = []
    for q in positions:
        motors.append(MotorCmd_(mode=1, q=q, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=[0, 0, 0]))
    cmd = MotorCmds_()
    cmd.cmds = motors
    return cmd

def both_hands(pinky, ring, middle, index, thumb_bend, thumb_rot):
    h = [pinky, ring, middle, index, thumb_bend, thumb_rot]
    return h + h

def send_inspire(pub, positions, duration=2.0):
    cmd = make_inspire_cmd(positions)
    steps = int(duration / 0.02)
    for _ in range(steps):
        pub.Write(cmd)
        time.sleep(0.02)

# === Main ===
def main():
    global low_state

    ChannelFactoryInitialize(1)
    crc = CRC()

    # Publishers
    arm_pub = ChannelPublisher("rt/lowcmd", LowCmd_)
    arm_pub.Init()

    inspire_pub = ChannelPublisher("rt/inspire/cmd", MotorCmds_)
    inspire_pub.Init()

    # Subscriber
    state_sub = ChannelSubscriber("rt/lowstate", LowState_)
    state_sub.Init(on_low_state, 10)

    print("Waiting for lowstate...")
    while low_state is None:
        time.sleep(0.1)
    print("Got lowstate!")

    # Save initial arm positions
    init_arm_pos = []
    for joint in ARM_JOINTS:
        init_arm_pos.append(float(low_state.motor_state[joint].q))
    print(f"Initial arm positions: {[f'{v:.2f}' for v in init_arm_pos]}")

    low_cmd = unitree_hg_msg_dds__LowCmd_()
    dt = 0.02
    kp = 60.0
    kd = 1.5

    # --- Phase 1: Raise arms (3 seconds) ---
    print("\n=== Phase 1: Raising arms ===")
    duration = 3.0
    t = 0.0
    while t < duration:
        ratio = np.clip(t / duration, 0.0, 1.0)
        for i, joint in enumerate(ARM_JOINTS):
            low_cmd.motor_cmd[joint].q = (1.0 - ratio) * init_arm_pos[i] + ratio * ARM_TARGET[i]
            low_cmd.motor_cmd[joint].dq = 0.0
            low_cmd.motor_cmd[joint].tau = 0.0
            low_cmd.motor_cmd[joint].kp = kp
            low_cmd.motor_cmd[joint].kd = kd
        low_cmd.crc = crc.Crc(low_cmd)
        arm_pub.Write(low_cmd)
        time.sleep(dt)
        t += dt
    print("Arms raised!")

    # Keep arms in position during countdown
    def keep_arms():
        for i, joint in enumerate(ARM_JOINTS):
            low_cmd.motor_cmd[joint].q = ARM_TARGET[i]
            low_cmd.motor_cmd[joint].dq = 0.0
            low_cmd.motor_cmd[joint].tau = 0.0
            low_cmd.motor_cmd[joint].kp = kp
            low_cmd.motor_cmd[joint].kd = kd
        low_cmd.crc = crc.Crc(low_cmd)
        arm_pub.Write(low_cmd)

    # --- Phase 2: Countdown ---
    print("\n=== Phase 2: Countdown ===")
    time.sleep(1)

    countdown_poses = [
        ("5 - all open",              both_hands(O, O, O, O, O, O)),
        ("4 - thumb folded",          both_hands(O, O, O, O, C, C)),
        ("3 - thumb+index folded",    both_hands(O, O, O, C, C, C)),
        ("2 - thumb+index+mid folded", both_hands(O, O, C, C, C, C)),
        ("1 - only pinky open",       both_hands(O, C, C, C, C, C)),
        ("0 - fist",                  both_hands(C, C, C, C, C, C)),
    ]

    for label, pos in countdown_poses:
        print(f"  {label}")
        inspire_cmd = make_inspire_cmd(pos)
        steps = int(2.0 / dt)
        for _ in range(steps):
            keep_arms()
            inspire_pub.Write(inspire_cmd)
            time.sleep(dt)
        time.sleep(0.5)

    # --- Phase 3: Return to open and lower arms ---
    print("\n=== Phase 3: Return ===")
    send_inspire(inspire_pub, both_hands(O, O, O, O, O, O), duration=2.0)

    print("Lowering arms...")
    t = 0.0
    duration = 3.0
    while t < duration:
        ratio = np.clip(t / duration, 0.0, 1.0)
        for i, joint in enumerate(ARM_JOINTS):
            low_cmd.motor_cmd[joint].q = (1.0 - ratio) * ARM_TARGET[i] + ratio * init_arm_pos[i]
            low_cmd.motor_cmd[joint].dq = 0.0
            low_cmd.motor_cmd[joint].tau = 0.0
            low_cmd.motor_cmd[joint].kp = kp
            low_cmd.motor_cmd[joint].kd = kd
        low_cmd.crc = crc.Crc(low_cmd)
        arm_pub.Write(low_cmd)
        time.sleep(dt)
        t += dt

    print("\n=== Done! ===")

if __name__ == "__main__":
    main()
ENDOFFILE

実行は、Inspireタスクのシミュレーションが起動している状態で別ターミナルから行います。

conda activate unitree_sim_env
cd ~/unitree_sim_isaaclab
python inspire_full_demo.py

実機へのデプロイ

G1の内部構成

G1の内部には2台のコンピュータがあります。

PC 役割 IP 備考
ロコモーションコンピュータ 歩行制御・バランス制御 192.168.123.161 ユーザー開発不可
開発コンピュータ ユーザーの開発用 192.168.123.164 SSH可能

外部PCからはG1背面のEthernetポート(ポート4または5)にLANケーブルを繋ぎ、自分のPCのIPを192.168.123.xに設定して接続します。

開発コンピュータの環境構築

開発コンピュータにはWiFiカード(wlan0)が搭載されていますが、デフォルトではWiFiが無効化されています。WiFiを有効化してネットワークに接続できれば、通常通りpip3 installでパッケージをインストールできます。

今回は環境の都合で開発コンピュータからインターネットに接続できなかったため、外部PCからファイルを転送してオフラインでインストールする方法を取りました。開発コンピュータがインターネットに接続できる場合は、通常通りpip install cyclonedds==0.10.2等で済みます。

以下はオフラインインストールの手順です。

1. unitree_sdk2_pythonの転送とインストール

# 外部PCで
git clone https://github.com/unitreerobotics/unitree_sdk2_python.git
scp -r unitree_sdk2_python unitree@192.168.123.164:~/

# 開発コンピュータで
cd ~/unitree_sdk2_python
pip3 install --no-build-isolation --no-deps -e .

2. cyclonedds(Pythonバインディング)のインストール

開発コンピュータにはcycloneddsのCライブラリがプリインストールされています(/home/unitree/cyclonedds_ws/install/cyclonedds)。Pythonバインディングのみソースからビルドします。

# 外部PCでtar.gzをダウンロードして転送
curl -L -o cyclonedds-0.10.2.tar.gz https://files.pythonhosted.org/packages/62/88/4b440f5916976234838989c3214222a5abc6fd48009a992c4dc22a86c04f/cyclonedds-0.10.2.tar.gz
scp cyclonedds-0.10.2.tar.gz unitree@192.168.123.164:~/

# 開発コンピュータで
tar xzf cyclonedds-0.10.2.tar.gz
cd cyclonedds-0.10.2
CYCLONEDDS_HOME=/home/unitree/cyclonedds_ws/install/cyclonedds pip3 install --no-build-isolation --no-deps .

開発コンピュータのシステム時刻が1970年になっている場合、ZIPのタイムスタンプエラーが発生します。その場合は事前にsudo date -s "2026-04-10 20:00:00"のように時刻を設定してください。

3. typing_extensionsの転送とインストール

cycloneddsの依存パッケージです。

# 外部PCで
pip3 download typing_extensions --no-deps -d /tmp/te_pkg --platform manylinux1_aarch64 --python-version 38 --only-binary=:all:
scp /tmp/te_pkg/typing_extensions-*.whl unitree@192.168.123.164:~/

# 開発コンピュータで
pip3 install --no-deps ~/typing_extensions-*.whl

4. DFX_inspire_serviceのビルド

RH56DFX(RH56DFQ)のDDS↔RS485変換ミドルウェアです。

# 外部PCで
git clone https://github.com/unitreerobotics/dfx_inspire_service.git
scp -r dfx_inspire_service unitree@192.168.123.164:~/

# 開発コンピュータで
cd ~/dfx_inspire_service
mkdir build && cd build
cmake ..
make -j6

実機用デモスクリプト

実機ではG1ArmActionClientの「hands up」アクションで腕を上げてからカウントダウンを実行します。シミュレータではrt/lowcmdで腕を制御しましたが、実機ではG1の内部サービスと連携するRPCベースのインターフェースが使えます。

cat << 'ENDOFFILE' > ~/inspire_real_demo.py
import time
import sys
from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize
from unitree_sdk2py.idl.unitree_go.msg.dds_ import MotorCmds_, MotorCmd_
from unitree_sdk2py.g1.arm.g1_arm_action_client import G1ArmActionClient, action_map

O = 1.0  # open
C = 0.0  # close

def make_cmd(positions):
    motors = []
    for q in positions:
        motors.append(MotorCmd_(mode=1, q=q, dq=0.0, tau=0.0, kp=0.0, kd=0.0, reserve=[0, 0, 0]))
    cmd = MotorCmds_()
    cmd.cmds = motors
    return cmd

def both_hands(pinky, ring, middle, index, thumb_bend, thumb_rot):
    h = [pinky, ring, middle, index, thumb_bend, thumb_rot]
    return h + h

def send_pose(pub, positions, duration=2.0):
    cmd = make_cmd(positions)
    steps = int(duration / 0.02)
    for _ in range(steps):
        pub.Write(cmd)
        time.sleep(0.02)

def main():
    if len(sys.argv) < 2:
        print("Usage: python3 inspire_real_demo.py <network_interface>")
        print("Example: python3 inspire_real_demo.py eth0")
        sys.exit(1)

    iface = sys.argv[1]

    print("WARNING: Robot will move its arms and hands!")
    print("Make sure G1 is standing and area is clear.")
    input("Press Enter to continue...")

    ChannelFactoryInitialize(0, iface)

    # Inspire Hand publisher
    inspire_pub = ChannelPublisher("rt/inspire/cmd", MotorCmds_)
    inspire_pub.Init()

    # Arm action client
    arm_client = G1ArmActionClient()
    arm_client.SetTimeout(10.0)
    arm_client.Init()

    # --- Phase 1: Raise arms ---
    print("\n=== Phase 1: Raising arms ===")
    arm_client.ExecuteAction(action_map["hands up"])
    time.sleep(3)

    # --- Phase 2: Countdown ---
    print("\n=== Phase 2: Countdown ===")
    countdown_poses = [
        ("5 - all open",              both_hands(O, O, O, O, O, O)),
        ("4 - thumb folded",          both_hands(O, O, O, O, C, C)),
        ("3 - thumb+index folded",    both_hands(O, O, O, C, C, C)),
        ("2 - thumb+index+mid folded", both_hands(O, O, C, C, C, C)),
        ("1 - only pinky open",       both_hands(O, C, C, C, C, C)),
        ("0 - fist",                  both_hands(C, C, C, C, C, C)),
    ]

    for label, pos in countdown_poses:
        print(f"  {label}")
        send_pose(inspire_pub, pos, duration=2.0)
        time.sleep(0.5)

    # --- Phase 3: Return ---
    print("\n=== Phase 3: Return ===")
    send_pose(inspire_pub, both_hands(O, O, O, O, O, O), duration=2.0)
    time.sleep(1)
    arm_client.ExecuteAction(action_map["release arm"])
    time.sleep(2)

    print("\n=== Done! ===")

if __name__ == "__main__":
    main()
ENDOFFILE

実行手順

G1をリモコンでオペレーションコントロール状態にした上で、開発コンピュータにSSH接続して実行します。

オペレーションコントロール状態への遷移手順(ファームウェアバージョンにより異なります):

  1. 起動後、ダンピングモードにする
  2. レディ状態にする
  3. オペレーションコントロールにする

ボタンの組み合わせはファームウェアバージョンによって異なるため、リモコンに貼付されているコマンド表またはUnitree Explore Appのリモコンユーザーマニュアルを参照してください。

ターミナル1: RH56DFQミドルウェア起動

cd ~/dfx_inspire_service/build
sudo ./inspire_g1

ターミナル2: デモ実行

cd ~
python3 inspire_real_demo.py eth0

G1ArmActionClientの「hands up」で両腕が上がり、その後ハンドがカウントダウンを実行します。
https://youtu.be/8K1BWNNcXCg?si=AO-nxA2a9HHqqfop

実機での腕ポーズについて

シミュレータではrt/lowcmd経由で腕の関節角度を自由に調整し、手のひらを正面に向けて前腕を立てるポーズ(ShoulderPitch=-0.5, Elbow=-1.4, WristRoll=±1.57)を作りました。実機でも同じポーズを再現するためにrt/arm_sdkを使ったスクリプト(v2)も用意しましたが、こちらは以下の問題が発生しました。

  • 上半身を前に屈めてしまい、バランスを崩して転倒しかける
  • 指を1本折り曲げるたびに肘がすごい勢いで真っ直ぐに伸び、再び肘を曲げてから次の指を折るという不安定な挙動

rt/arm_sdkはロコモーションコンピュータと協調するよう設計されていますが、カウントダウン中に腕のポーズを維持しつつRH56DFQのコマンドを同時に送り続ける処理で、制御の競合が起きていた可能性があります。この問題の調整には追加の検証が必要です。

最終的に、実機のデモ動画はG1ArmActionClientの「hands up」を使ったv1スクリプトで撮影しました。「hands up」のポーズはシミュレータで調整したものとは肘の角度や手のひらの向きが異なりますが、G1の内部サービスが提供する定義済みアクションのため、バランス制御との協調が安定しており、カウントダウン中もスムーズに動作しました。

シミュレータと実機で挙動が異なる点は今回のsim-to-realにおけるギャップの一つです。rt/arm_sdkでの自由なポーズ制御と安定性の両立は今後の課題として残りました。

https://youtube.com/shorts/FAvKY2arOBQ?si=VyPHXPx0GWooEiuC

DDS接続の確認方法

実機でスクリプトは動くのに何も反応しない場合、DDSの通信を確認します。

python3 -c "
import time
from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize
from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowState_

received = False
def handler(msg):
    global received
    if not received:
        print(f'Received lowstate! tick={msg.tick}')
        received = True

ChannelFactoryInitialize(0, 'eth0')
sub = ChannelSubscriber('rt/lowstate', LowState_)
sub.Init(handler, 10)
print('Waiting for lowstate...')
time.sleep(5)
if not received:
    print('No data. DDS not connected.')
else:
    print('DDS OK!')
"

データを受信できればDDS通信は正常です。ロボットがオペレーションコントロール状態でないとアームのアクションは実行されない点に注意してください。

まとめ

今回のカウントダウンはシンプルなデモであり、DDSプロトコルが共通であるため、シミュレータで書いたコードのロジック部はそのまま実機にも適用できました。

一方で、シミュレータで調整した腕のポーズを実機にそのまま持っていくと、バランス制御との競合で不安定になるというsim-to-realのギャップも確認できました。今回は定義済みのアクションを使うことで安定した動作を実現しましたが、自由なポーズでの安定制御は今後の課題です。

この記事をシェアする

関連記事