mujoco读取模型几何体属性。
模型xml文件信息如下:
bash
<mujoco>
<worldbody>
<light diffuse="0.5 0.5 0.5" pos="0 0 3" dir="0 0 -1"/>
<geom name="ground" type="plane" size="1 1 0.1" rgba="0.5 0.5 0.5 1"/>
<!-- 立方体 -->
<body name="cube" pos="0 0 1">
<joint type="free"/>
<geom name="cube" type="box" size="0.1 0.1 0.1" rgba="0.0 0.0 0.5 1"/>
</body>
<!-- 圆柱体 -->
<body name="cylinder" pos="-0.5 0.3 0.8">
<joint type="free"/>
<!-- size参数:第一个值是半径,第二个值是高度 -->
<geom name="cylinder" type="cylinder" size="0.08 0.15" rgba="0.0 0.5 0.0 1"/>
</body>
<!-- 圆柱体2 -->
<body name="cylinder2" pos="0.25 0.1 0.9">
<joint type="free"/>
<!-- size参数:第一个值是半径,第二个值是高度 -->
<geom name="cylinder2" type="cylinder" size="0.08 0.15" rgba="0.5 0.1 0.7 1"/>
</body>
<!-- 球体 -->
<body name="sphere" pos="0.5 0.5 0.7">
<joint type="free"/>
<!-- size参数:球体半径 -->
<geom name="sphere" type="sphere" size="0.09" rgba="1.0 0.5 0.0 1"/>
</body>
<!-- 胶囊体(capsule) -->
<body name="capsule" pos="0.6 -0.3 0.4">
<joint type="free"/>
<!-- size:第一个值=半径,第二个值=中心圆柱高度(总高度=高度+2*半径) -->
<geom name="capsule" type="capsule" size="0.07 0.2" rgba="0.2 0.8 0.8 1"/>
</body>
<!-- 椭球体(ellipsoid) -->
<body name="ellipsoid" pos="-0.2 0.6 0.3">
<joint type="free"/>
<!-- size:x/y/z轴的半径(三个值不同则为椭球,相同则等价于球体) -->
<geom name="ellipsoid" type="ellipsoid" size="0.12 0.08 0.1" rgba="0.8 0.8 0.2 1"/>
</body>
</worldbody>
</mujoco>
以下是脚本:
1)加载xml文件,初始化模型。
2)读取模型的几何信息。
3)仿真、可视化模型。
bash
#-*-coding:utf-8-*-
# date:2025-12-07
# Author: Eric
import mujoco
import mujoco.viewer
import time
# 初始化MuJoCo模型和数据
model = mujoco.MjModel.from_xml_path("geom.xml")
data = mujoco.MjData(model)
print("几何体数量:",model.ngeom)
print("-----------------------------")
print("model.geom_rgba type:",type(model.geom_rgba))
print("model.geom_rgba shape:",model.geom_rgba.shape)
print("几何体颜色具体信息:",model.geom_rgba)
print("-----------------------------")
# 遍历所有几何体
print("\n各几何体详情:\n")
for i in range(model.ngeom):
geom_name = model.geom(i).name if model.geom(i).name else f"unnamed_geom_{i}"
geom_type = mujoco.mjtGeom(model.geom_type[i]).name.lower()
print(f"索引{i}:名称={geom_name},类型={geom_type} ,颜色信息={model.geom_rgba[i]}")
# 仿真循环(带可视化)
with mujoco.viewer.launch_passive(model, data) as viewer:
# 固定仿真帧率
viewer._paused = False
start_time = time.time()
while viewer.is_running():
# 运行一步仿真
mujoco.mj_step(model, data)
# 同步可视化
viewer.sync()
# 控制仿真帧率(避免过快)
time.sleep(model.opt.timestep)
输出log信息如下:
bash
几何体数量: 7
-----------------------------
model.geom_rgba type: <class 'numpy.ndarray'>
model.geom_rgba shape: (7, 4)
几何体颜色具体信息: [[0.5 0.5 0.5 1. ]
[0. 0. 0.5 1. ]
[0. 0.5 0. 1. ]
[0.5 0.1 0.7 1. ]
[1. 0.5 0. 1. ]
[0.2 0.8 0.8 1. ]
[0.8 0.8 0.2 1. ]]
-----------------------------
各几何体详情:
索引0:名称=ground,类型=mjgeom_plane ,颜色信息=[0.5 0.5 0.5 1. ]
索引1:名称=cube,类型=mjgeom_box ,颜色信息=[0. 0. 0.5 1. ]
索引2:名称=cylinder,类型=mjgeom_cylinder ,颜色信息=[0. 0.5 0. 1. ]
索引3:名称=cylinder2,类型=mjgeom_cylinder ,颜色信息=[0.5 0.1 0.7 1. ]
索引4:名称=sphere,类型=mjgeom_sphere ,颜色信息=[1. 0.5 0. 1. ]
索引5:名称=capsule,类型=mjgeom_capsule ,颜色信息=[0.2 0.8 0.8 1. ]
索引6:名称=ellipsoid,类型=mjgeom_ellipsoid ,颜色信息=[0.8 0.8 0.2 1. ]
可视化结果如下:
