Open Duck Mini V2 文档

搭建问题记录

目录

资料导航

硬件组装

电机配置

电机驱动板供电,并且 Type-C 连接电脑或树莓派。Windows 电脑可以使用 FT 上位机修改 ID。电机设置参考:舵机配置

关节和ID对应关系

这里的脚本 scripts/configure_motor.py 会设置电机的 ID,PID,和位置,新电机默认检测 ID 1,然后修改至输入 ID,如果电机之前已经配置好 ID,则需要注释行 io.change_id({current_id: int(args.id)})

注意,校准后的位置为中位,在 FT 上查看是 2048
参考后续用串口设置 2048 更安全。
切勿直接使用 FT 设置为 0,有个问题是到达 4095 需要绕一整圈。装配好后,肯定是无法做到的,会发生堵转。

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
# 运行
# python scripts/configure_motor.py --port <COM port> --id <id>

kp = io.get_P_coefficient([current_id])
ki = io.get_I_coefficient([current_id])
kd = io.get_D_coefficient([current_id])
max_acceleration = io.get_maximum_acceleration([current_id])
acceleration = io.get_acceleration([current_id])
mode = io.get_mode([current_id])

# print(f"PID : {kp}, {ki}, {kd}")
# print(f"max_acceleration: {max_acceleration}")
# print(f"acceleration: {acceleration}")
# print(f"mode: {mode}")

io.set_lock({current_id: 0})
io.set_mode({current_id: 0})
io.set_maximum_acceleration({current_id: 0})
io.set_acceleration({current_id: 0})
io.set_P_coefficient({current_id: 32})
io.set_I_coefficient({current_id: 0})
io.set_D_coefficient({current_id: 0})
io.change_id({current_id: int(args.id)}) # 如果电机 ID 已经配置,而查看其他信息,注释这行

current_id = int(args.id)

time.sleep(1)

io.set_goal_position({current_id: 0})

time.sleep(1)

在表格中,修改这里的 ID 号和自定义位置,这样电机就会设置当前位置,改为2048。

自定义指令生成

名称ID当前位置 0当前位置 2048
right_hip_yaw10FF FF 0A 04 0B 00 00 E6FF FF 0A 04 0B 00 08 DE
right_hip_roll11FF FF 0B 04 0B 00 00 E5FF FF 0B 04 0B 00 08 DD
right_hip_pitch12FF FF 0C 04 0B 00 00 E4FF FF 0C 04 0B 00 08 DC
right_knee13FF FF 0D 04 0B 00 00 E3FF FF 0D 04 0B 00 08 DB
right_ankle14FF FF 0E 04 0B 00 00 E2FF FF 0E 04 0B 00 08 DA
left_hip_yaw20FF FF 14 04 0B 00 00 DCFF FF 14 04 0B 00 08 D4
left_hip_roll21FF FF 15 04 0B 00 00 DBFF FF 15 04 0B 00 08 D3
left_hip_pitch22FF FF 16 04 0B 00 00 DAFF FF 16 04 0B 00 08 D2
left_knee23FF FF 17 04 0B 00 00 D9FF FF 17 04 0B 00 08 D1
left_ankle24FF FF 18 04 0B 00 00 D8FF FF 18 04 0B 00 08 D0
neck_pitch30FF FF 1E 04 0B 00 00 D2FF FF 1E 04 0B 00 08 CA
head_pitch31FF FF 1F 04 0B 00 00 D1FF FF 1F 04 0B 00 08 C9
head_yaw32FF FF 20 04 0B 00 00 D0FF FF 20 04 0B 00 08 C8
head_roll33FF FF 21 04 0B 00 00 CFFF FF 21 04 0B 00 08 C7
  • roll,x 轴,垂直纸面
  • pitch,y 轴,水平
  • yaw,z 轴,竖直

参考:欧拉角Pitch、Roll、Yaw介绍

欧拉角

电路连接

模块连接示意图

模块连接示意图

为了安全起见,请确保在将电池放入电池座之前,所有电池单元已充电至相同的电压。

电源连接示意图:

  • 注意充放电保护板 BMS 直接输出的 8.4V 给电机驱动板和稳压板 UBEC 供电
  • 稳压板的 EN 短接帽要拿掉。红灯亮时表示有输出
  • UBEC 输出 5V 给头部各模块供电

保护电路连接示意图:

充电电路示意图:

  • 充满时,红灯亮,绿灯也亮
  • 电池电量不足充电时,红灯亮,绿灯不亮

脚部接触开关连接

调试

Runtime 设置文档:

运行时

1
2
3
4
git clone https://github.com/apirrone/Open_Duck_Mini_Runtime
cd Open_Duck_Mini_Runtime
git checkout v2
pip install -e .
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
python scripts/calibrate_imu.py
Calibrated : False
Calibration status: (3, 0, 3, 3)
Calibrated : False
Calibration status: (3, 0, 3, 3)
Calibrated : False
Calibration status: (3, 0, 3, 3)
Calibrated : False
Calibration status: (3, 0, 3, 3)
Calibrated : False
Calibration status: (3, 3, 3, 3)
Calibrated : True
CALIBRATION DONE
offsets_accelerometer (-57, -23, -12)
offsets_gyroscope (3, -4, 1)
offsets_magnetometer (-1354, 274, 368)
Saved imu_calib_data.pkl

python3 mini_bdx_runtime/mini_bdx_runtime/raw_imu.py
分量含义范围说明
sys系统整体校准状态0–3依赖于 gyro/accel/mag 的状态
gyro陀螺仪校准状态0–3静止即可自动完成
accel加速度计校准状态0–3多方向移动以完成
mag磁力计校准状态0–3环境干净下旋转设备可完成

各模块校准条件说明

🌀 Gyro(陀螺仪):

  • 只需要 静止几秒 即可完成。
  • 如果你一直在晃动设备,它可能永远达不到 3。

🧭 Magnetometer(磁力计):

  • 需要在远离金属、磁场干扰的环境中,多角度旋转设备。
  • 室内环境常常干扰大,很难校准到 3。

📐 Accelerometer(加速度计):

  • 需要你在多个方向上轻轻移动或旋转设备。
  • 不用剧烈甩动,类似于「画圈、倾斜」。

🧠 System(系统):

  • 综合其他三个分量,取决于它们的校准状态。

sim2real

1
2
3
4
5
6
7
8
9
10
11
12
13
14
pip install onshape-to-robot
export PATH=$PATH:/home/sjl/.local/bin

# .bashrc
# Obtained at https://dev-portal.onshape.com/keys
export ONSHAPE_API=https://cad.onshape.com
export ONSHAPE_ACCESS_KEY="ewGlcCa0TIIDRLd48DpxgwBA"
export ONSHAPE_SECRET_KEY="SneSiDla3DpJX0fjCf0VXPyVWWiEZmNW6n46In6FGxm2H9ID"

$env:ONSHAPE_API = "https://cad.onshape.com"
$env:ONSHAPE_ACCESS_KEY = "ewGlcCa0TIIDRLd48DpxgwBA"
$env:ONSHAPE_SECRET_KEY = "SneSiDla3DpJX0fjCf0VXPyVWWiEZmNW6n46In6FGxm2H9ID"

mkdir duck

duck/config.json:

1
2
3
4
5
6
{
// Onshape URL of the assembly
"url": "https://cad.onshape.com/documents/64074dfcfa379b37d8a47762/w/3650ab4221e215a4f65eb7fe/e/0505c262d882183a25049d05",
// Output format
"output_format": "urdf"
}
1
onshape-to-robot duck


1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
wget https://github.com/google-deepmind/mujoco/releases/download/3.3.2/mujoco-3.3.2-linux-x86_64.tar.gz
tar xvf mujoco-3.3.2-linux-x86_64.tar.gz
export PATH=$PATH:/opt/mujoco-3.3.2/bin

cd duck
mv assets/* . && rm -rf assets
compile robot.urdf scene.xml
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
Done.
First compile: 0.7649s
Second compile: 0.18s
1
2
3
4
python3 -m mujoco.viewer --mjcf=duck/scene.xml

# 或者上一级目录
onshape-to-robot-mujoco duck

安装 uv

1
2
3
4
5
curl -LsSf https://astral.sh/uv/install.sh | sh

# 网络不好时,使用pipx
sudo apt-get install pipx
pipx install uv
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
# 安装 git-lfs,不然无法 clone 大文件
sudo apt install git-lfs
git clone https://github.com/apirrone/Open_Duck_reference_motion_generator.git

# uv 换源
export UV_DEFAULT_INDEX="https://mirrors.aliyun.com/pypi/simple"

# 打开网页版仿真环境
uv run open_duck_reference_motion_generator/gait_playground.py --duck open_duck_mini_v2

# 生成动作
uv run scripts/auto_waddle.py -j8 --duck open_duck_mini_v2 --sweep

# 这将生成 polynomial_coefficients.pkl
uv run scripts/fit_poly.py --ref_motion recordings/

# 绘制
uv run scripts/plot_poly_fit.py --coefficients polynomial_coefficients.pkl

# 重放
uv run scripts/replay_motion.py -f recordings/<file>.json

机器鸭资源文件:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
cd Open_Duck_reference_motion_generator/open_duck_reference_motion_generator/robots/open_duck_mini_v2

.
├── assets
│ ├── antenna.part
│ ├── antenna.stl
│ ├── ... # 模型文件
│ ├── wj-wk00-0124bottomcase_45.part
│ └── wj-wk00-0124bottomcase_45.stl
├── auto_gait.json # 步态文件
├── open_duck_mini_v2.urdf
├── placo_defaults.json # 仿真默认值
└── placo_presets
├── fast.json
└── medium.json # 预设,auto_waddle.py 采用

第一步,加载 auto_gait.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
38
{
// 1. 速度档位定义
"slow": 0.05, // 慢速模式
"medium": 0.1, // 中速模式
"fast": 0.15, // 快速模式

// 2. 运动范围限制
// 限制机器鸭的 最大运动速度,防止因速度过快导致失稳。
"dx_max": [0, 0.05], // X 方向(前进/后退)速度范围(m/s)
"dy_max": [0, 0.05], // Y 方向(侧向)速度范围(m/s)
"dtheta_max": [0, 0.25], // 旋转角速度范围(rad/s)

// 3. 参数扫描范围(Sweep Range)
// 3.1 足端轨迹扫描范围
// 调整 脚掌落地点位置
"min_sweep_x": -0.04, // 足端 X 方向最小偏移(m,负值表示向后)
"max_sweep_x": 0.06, // 足端 X 方向最大偏移(m,正值表示向前)
"min_sweep_y": -0.03, // 足端 Y 方向最小偏移(m,负值表示向左)
"max_sweep_y": 0.03, // 足端 Y 方向最大偏移(m,正值表示向右)
"min_sweep_theta": -0.3, // 足端最小旋转角度(rad,负值表示逆时针)
"max_sweep_theta": 0.3, // 足端最大旋转角度(rad,正值表示顺时针)

// 3.2 扫描粒度(Granularity)
// 控制参数扫描的 精细程度,值越小优化越精细,但计算量越大。
"sweep_xy_granularity": 0.02, // XY 方向扫描步长(m)
"sweep_theta_granularity": 0.07 // 旋转角度扫描步长(rad)
}

足端运动范围(俯视图):
+Y(左)
|
-X(后)---+---+X(前)
|
-Y(右)

X 方向扫描:-0.04m(后) → 0.06m(前)
Y 方向扫描:-0.03m(左) → 0.03m(右)
θ 旋转扫描:-0.3rad(逆时针) → 0.3rad(顺时针)

调整建议:

  • 若机器人行走不稳:
    • 减小 dx_max 或 dtheta_max,降低运动速度。
    • 增大 double_support_ratio(需在另一个配置文件中调整)。
  • 若步态不自然:
    • 调整 sweep_x/y 范围,限制脚掌移动幅度。
    • 减小 sweep_xy_granularity,使优化更精细。
  • 若优化耗时过长:
    • 增大 sweep_theta_granularity,减少旋转角度的尝试次数。

定义机器鸭典型步态运动模式 gait_motions :(没有用到)

  1. standing
  2. forward 直线前进
  3. backward 直线后退
  4. left
  5. right
  6. ang_left 逆时针旋转
  7. ang_right 顺时针旋转
  8. dia_forward 沿对角线方向前进(如 X+Y 方向组合)
  9. dia_backward 沿对角线方向后退(如 -X+Y 方向组合)。

动作生成:

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
# ---------------------------------------------------------------
# 3. Generate random presets (n times)
# "medium" and "fast" as example base speeds
# ---------------------------------------------------------------
# 预设速度档位(当前仅使用"medium","fast"被注释)
preset_speeds = ["medium"] # , "fast"]

# 判断是否启用参数扫描模式(--sweep参数)
if args.sweep:
# 生成X方向(前后)的扫描范围数组,步长为sweep_xy_granularity
dxs = np.arange(min_sweep_x, max_sweep_x + sweep_xy_granularity, sweep_xy_granularity)
# 生成Y方向(左右)的扫描范围数组
dys = np.arange(min_sweep_y, max_sweep_y + sweep_xy_granularity, sweep_xy_granularity)
# 生成旋转角度(theta)的扫描范围数组,步长为sweep_theta_granularity
dthetas = np.arange(min_sweep_theta, max_sweep_theta + sweep_theta_granularity, sweep_theta_granularity)
# 计算总参数组合数 = X方向点数 * Y方向点数 * 角度点数
all_n = len(dxs) * len(dys) * len(dthetas)
else:
# 非扫描模式时,使用命令行指定的生成数量(--num参数)
all_n = args.num

# 打印生成动作数量的提示信息
nb_moves_message = f"=== GENERATING {all_n} MOVES ==="
spacer = "=" * len(nb_moves_message)
print(spacer)
print(nb_moves_message)
print(spacer)

# 存储所有生成的命令
commands = []
for i in range(all_n):
# 随机选择一个基准速度(当前只有"medium"可选)
selected_speed = np.random.choice(preset_speeds)
# 构建对应速度预设文件的路径
preset_file = os.path.join(presets_dir, f"{selected_speed}.json")

# 检查预设文件是否存在
if not os.path.isfile(preset_file):
raise FileNotFoundError(f"Preset file not found: {preset_file}")

# 加载预设文件内容
with open(preset_file, "r") as file:
data = json.load(file)

# 参数扫描模式处理
if args.sweep:
# 计算当前迭代对应的参数索引:
# dx_idx: 取模保证在X方向范围内循环
dx_idx = i % len(dxs)
# dy_idx: 整除X方向长度后取模
dy_idx = (i // len(dxs)) % len(dys)
# dtheta_idx: 整除(X*Y方向长度)后取模
dtheta_idx = (i // (len(dxs) * len(dys))) % len(dthetas)

# 更新运动参数(保留2位小数)
data["dx"] = round(dxs[dx_idx], 2) # X方向位移
data["dy"] = round(dys[dy_idx], 2) # Y方向位移
data["dtheta"] = round(dthetas[dtheta_idx], 2) # 旋转角度
else:
# 随机模式处理:在最大范围内随机生成参数
data["dx"] = round(
np.random.uniform(dx_max[0], dx_max[1]) * np.random.choice([-1, 1]), 2 # 随机正负方向
)
data["dy"] = round(
np.random.uniform(dy_max[0], dy_max[1]) * np.random.choice([-1, 1]), 2
)
data["dtheta"] = round(
np.random.uniform(dtheta_max[0], dtheta_max[1]) * np.random.choice([-1, 1]),
2,
)

# 将修改后的预设保存到临时文件
tmp_preset = os.path.join(tmp_dir, f"{i}_{selected_speed}.json")
with open(tmp_preset, "w") as out_file:
json.dump(data, out_file, indent=4)

# 构建调用gait_generator.py的命令
cmd = [
"python",
f"{SCRIPT_PATH}/../open_duck_reference_motion_generator/gait_generator.py",
"--duck", args.duck, # 指定机器人类型
"--preset", tmp_preset, # 使用临时预设文件
"--name", str(i), # 用序号作为动作名称
"--output_dir", args.output_dir, # 指定输出目录
]
# 若非详细模式,则将日志输出到文件
log_file = None if args.verbose else os.path.join(log_dir, f"{i}.log")
# 将命令和日志路径存入列表
commands.append((cmd, log_file))

所有的生成基于 open_duck_reference_motion_generator/robots/go_bdx/placo_presets/medium.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
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
{
"dx": 0.0, // 机器鸭在 X 轴(前进方向) 的目标速度(单位:m/s)
"dy": 0.0, // 机器鸭在 Y 轴(侧向) 的目标速度(单位:m/s)。
"dtheta": 0.0, // 机器鸭的 目标旋转角速度(单位:rad/s)
"duration": 2, // 步态规划的总持续时间(单位:秒)
"hardware": true, // 表示使用 真实硬件(如实际机器人)
"trunk_mode": true,
"double_support_ratio": 0.2, // 双足支撑阶段 占整个步态周期的比例(20%)
"startend_double_support_ratio": 1.5, // 起始和结束阶段的双足支撑时间延长比例(1.5 倍)。
"planned_timesteps": 48, // 步态规划的总时间步数(影响运动平滑度)。
"replan_timesteps": 10, // 每隔多少时间步 重新规划一次步态(动态调整)。
"walk_com_height": 0.27, // 质心(COM)高度(单位:米),影响机器人平衡。
"walk_foot_height": 0.025, // 抬脚高度(单位:米),影响步态流畅性。
"walk_trunk_pitch": -2, // 躯干俯仰角(单位:度),负值表示轻微前倾。
"walk_foot_rise_ratio": 0.1, // 抬脚阶段的占比(20% 用于抬脚,80% 用于摆动)。
"single_support_duration": 0.30, // 单足支撑阶段持续时间(单位:秒)
"single_support_timesteps": 10, // 单足支撑阶段的时间步数
"foot_length": 0.16, // 脚掌长度(单位:米),影响 ZMP(零力矩点)计算。
"feet_spacing": 0.19, // 两脚之间的横向间距(单位:米)。
"zmp_margin": 0.0, // ZMP 安全裕度(防止机器人因重心偏移而摔倒)。
"foot_zmp_target_x": 0.0, // ZMP 目标位置(通常设置在脚掌中心)。
"foot_zmp_target_y": -0.04,
"walk_max_dtheta": 1.0, // 最大旋转角速度(单位:rad/s)
"walk_max_dy": 0.1, // 最大侧向速度(单位:m/s)。
"walk_max_dx_forward": 0.1, // 最大前进速度(单位:m/s)
"walk_max_dx_backward": 0.1, // 最大后退速度(单位:m/s)
"joints": [
"left_hip_yaw",
"left_hip_roll",
"left_hip_pitch",
"left_knee",
"left_ankle",
"neck_pitch",
"head_pitch",
"head_yaw",
"head_roll",
"left_antenna",
"right_antenna",
"right_hip_yaw",
"right_hip_roll",
"right_hip_pitch",
"right_knee",
"right_ankle"
],
"joint_angles": {
"head_pitch": 0, // 头部俯仰角
"head_yaw": 0, // 头部偏航角
"head_roll": 0,
"neck_pitch": 0, // 颈部俯仰角
"left_antenna": 0,
"right_antenna": 0
}
}

以下是对 open_duck_reference_motion_generator/gait_generator.py 代码的详细注释和功能分析:

1. 核心功能概述
这段代码实现了一个基于 Flask Web框架机器鸭步态生成与可视化系统,主要功能包括:

  • 通过Web界面实时调整步态参数(速度、步长、支撑时间等)
  • 可视化机器鸭的运动状态(三维模型+足部轨迹)
  • 支持多种机器鸭模型(go_bdx/open_duck_mini等)
  • 生成可保存的运动轨迹数据

2. 关键模块分析

(1) 参数解析与初始化

1
2
3
4
5
6
7
8
9
10
# 使用argparse解析命令行参数
parser = argparse.ArgumentParser()
parser.add_argument("--dx", type=float, default=0) # X方向速度
parser.add_argument("--dy", type=float, default=0) # Y方向速度
parser.add_argument("--dtheta", type=float, default=0) # 旋转速度
# ...(其他30+步态参数,如支撑时间、质心高度等)
args = parser.parse_args()

# 创建Flask应用
app = Flask(__name__)

(2) 步态参数管理类 GaitParameters

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
class GaitParameters:
def __init__(self):
# 根据机器人类型加载对应URDF模型路径
if args.duck == "open_duck_mini":
self.robot_urdf = "open_duck_mini.urdf"
self.asset_path = ".../open_duck_mini/"

def reset(self, pwe):
# 将参数应用到PlacoWalkEngine
pwe.parameters.double_support_ratio = self.double_support_ratio
# ...(同步所有参数)

def create_pwe(self):
# 创建Placo步行引擎实例
return PlacoWalkEngine(self.asset_path, self.robot_urdf)

(3) Web接口路由

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
@app.route('/run', methods=['POST'])
def run():
# 从表单获取参数并更新到gait对象
gait.dx = float(request.form['dx'])
gait.dy = float(request.form['dy'])
# ...(更新其他参数)
# 通知步态生成线程开始运行
global dorun
dorun = True

@app.route('/stop')
def stop():
# 停止运动生成
global run_loop
run_loop = False

(4) 步态生成线程

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
def gait_generator_thread():
while True:
if doreset: # 重置机器人
pwe = gait.create_pwe()
viz.display(pwe.robot.state.q)

if dorun: # 开始生成步态
pwe.set_traj(gait.dx, gait.dy, gait.dtheta)
while run_loop:
pwe.tick(DT) # 推进物理仿真
# 记录关键帧数据(位置/速度/接触状态)
if need_record_frame:
episode["Frames"].append(root_position + joints_positions + ...)
# 更新三维可视化
viz.display(pwe.robot.state.q)

3. 关键技术点

(1) 参数覆盖逻辑

1
2
3
4
5
6
7
# 优先级:命令行参数 > 预设文件 > 默认值
if args.double_support_ratio is not None:
gait_parameters['double_support_ratio'] = args.double_support_ratio
elif 'double_support_ratio' in gait_parameters:
pass # 使用预设文件值
else:
gait.double_support_ratio = 0.18 # 默认值

(2) 实时数据记录

1
2
3
4
5
6
7
8
9
10
11
12
# 记录每帧数据包含:
[
root_position, # 机身位置(x,y,z)
root_orientation, # 四元数姿态
joints_positions, # 所有关节角度
left_toe_pos, # 左脚位置(相对机身)
right_toe_pos, # 右脚位置
world_linear_vel, # 机身线速度
world_angular_vel, # 机身角速度
joints_vel, # 关节速度
foot_contacts # 足部接触状态(0/1)
]

(3) 可视化系统

  • 三维模型:通过robot_viz显示URDF模型
  • 足部轨迹footsteps_viz绘制支撑多边形
  • 坐标系robot_frame_viz显示机身/足部局部坐标系
1
2
3
4
5
git clone git@github.com:apirrone/Open_Duck_Playground.git

# 查看 mujoco, mujoco 配置参考上面
cd Open_Duck_Playground/playground/open_duck_mini_v2/xmls
python3 -m mujoco.viewer --mjcf=open_duck_mini_v2.xml

训练:

1
2
3
4
5
6
7
8
9
10
11
12
cd Open_Duck_Playground

# 将参考动作发生器的data拷贝过来
cp <path-to-polynomial_coefficients.pkl-in-open_duck_reference_motion_generator> \
playground/open_duck_mini_v2/data/polynomial_coefficients.pkl

# 遇到问题按照下面的提示解决
uv run playground/open_duck_mini_v2/runner.py

# 运行中下载 mujoco_menagerie 太久,可以先手动 clone
git clone git@github.com:google-deepmind/mujoco_menagerie.git
mv mujoco_menagerie ~/Open_Duck_Playground/.venv/lib/python3.10/site-packages/mujoco_playground/external_deps

训练遇到的问题:

现在可以愉快训练了:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
$ python playground/open_duck_mini_v2/runner.py

Every 0.1s: nvidia-smi DESKTOP-9DSK0U4: Sat May 31 13:57:08 2025
Sat May 31 13:57:08 2025
+-----------------------------------------------------------------------------------------+
| NVIDIA-SMI 575.57.04 Driver Version: 576.52 CUDA Version: 12.9 |
|-----------------------------------------+------------------------+----------------------+
| GPU Name Persistence-M | Bus-Id Disp.A | Volatile Uncorr. ECC |
| Fan Temp Perf Pwr:Usage/Cap | Memory-Usage | GPU-Util Compute M. |
| | | MIG M. |
|=========================================+========================+======================|
| 0 NVIDIA GeForce RTX 4070 ... On | 00000000:01:00.0 On | N/A |
| 35% 62C P2 171W / 220W | 11627MiB / 12282MiB | 100% Default |
| | | N/A |
+-----------------------------------------+------------------------+----------------------+

+-----------------------------------------------------------------------------------------+
| Processes: |
| GPU GI CI PID Type Process name GPU Memory |
| ID ID Usage |
|=========================================================================================|
| 0 N/A N/A 33660 C /python3.12 N/A |
+-----------------------------------------------------------------------------------------+