<mujoco model='humanoid'>
<compiler inertiafromgeom='true' angle='degree'/>
<!--自动判断geom的质量 -->
<!--角度制-->
<default>
<joint limited='true' damping='1' armature='0'/>
<!--range 的长度限制解除-->
<!--damping(阻尼)开启-->
<!—armature电机相关参数-->
<geom contype='1' conaffinity='1' condim='1' rgba='2 0.6 .4 1'
<!--设置物体之间可碰撞-->
<!--设置摩擦力-->
<!--rgba用于设置物体基础颜色,前三个参数是颜色参数,第四个是透明度0~1-->
margin="0.001" solref=".02 1" solimp=".8 .8 .01" material="geom"/>
<!--margin设置碰撞最小距离,只有两个geom距离低于margin的时候才会被判断为碰撞-->
<!—solref、solimp设置类似弹簧阻尼的东西,可以计算k和b-->
<motor ctrlrange='-.4 .4' ctrllimited='true'/>
<!—设置驱动范围-->
</default>
<option timestep='0.002' iterations="50" tolerance="1e-10" solver="Newton" jacobian="dense" cone="elliptic"/>
<!--设置步长为0.002-->
<!--设置迭代数为50-->
<!--设置误差阈值1e-10-->
<!—求解器用Newton-->
<!--设置雅可比自由度,60是dense,超过60是sparse-->
<!—cone=elliptic有真实的物理引擎,cone=pyramidal计算更快-->
<size nstack="1000000"/>
<!--设置堆栈最大数为1000000-->
<visual>
<map fogstart="3" fogend="5" force="0.1" znear="0.5"/>
<!—fogstart模拟线性雾,数字是雾的起始位置-->
<!—fogend为雾的结束位置-->
<!—force让力可视化,这个是可视化相关系数-->
<!—znear设置剪辑平面的位置,设置太近会导致深度缓冲的分辨率下降(通常情况下会很严重),而设置太远则会导致感兴趣的对象被剪切,从而无法放大。-->
<quality shadowsize="2048" offsamples="8"/>
<!--shadowsize该属性指定用于阴影映射的正方形纹理的大小。数值越高,阴影越平滑。-->
<!--offsample该属性指定离屏渲染的多样本数量。较大的值产生更好的抗锯齿,但会降低GPU的速度。-->
<global offwidth="800" offheight="800"/>
<!—设定缓冲区的宽度和高度。-->
</visual>
<asset>
<texture type="skybox" builtin="gradient" width="128" height="128" rgb1=".4 .6 .8"
rgb2="0 0 0"/>
<!—type纹理种类:skybox-->
<!—builtin=gradient纹理颜色梯度变化,从rgb1到rgb2-->
<!—纹理的宽度和高度是128-->
<texture name="texgeom" type="cube" builtin="flat" mark="cross" width="127" height="1278"
rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/>
<!--纹理名称:texgeom-->
<!—纹理种类:cube-->
<!—builtin=flat除底面填充rgb1,底面填充rgb2-->
<!—mark=cross图像中间标记十字,十字的颜色是markrgb-->
<!—markrgb渐变纹理标记-->
<!—random可以创造一个夜空外观-->
<texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2"
width="512" height="512"/>
<!--纹理种类:2d-->
<!—builtin=checker颜色rgb1和rgb2交替出现-->
<material name='MatPlane' reflectance='0.3' texture="texplane" texrepeat="1 1" texuniform="true"/>
<!—reflectance材质反射率-->
<!—texrepeat指定纹理重复次数-->
<!—texuniform=true,2d在空间中重复texrepeat次-->
<material name='geom' texture="texgeom" texuniform="true"/>
</asset>
<worldbody>
<geom name='floor' pos='0 0 0' size='5 5 .125' type='plane' material="MatPlane" condim='3'/>
<!—创建地板,位置在0 0 0,大小5 5 0.125,种类是平面,材料为之前定义的MatPlane,普通摩擦力-->
<light mode='targetbodycom' target='torso' directional='false'
diffuse='.8 .8 .8' specular='0.3 0.3 0.3' pos='0 0 4.0' dir='0 0 -1'/>
<!—targetbodycom光源位置不变,方向指向目标体子树质心-->
<!—目标体是torso-->
<!—directional光源是聚光灯源-->
<!—diffuse指定光源颜色-->
<!—specular指定高光颜色-->
<!—位置在0 0 4.0-->
<!—方向0 0 -1-->
<camera name='targeting' pos='1 1 2' mode='targetbodycom' target='torso'/>
<!—摄像机名称:targeting-->
<!—位置在1 1 2-->
<!—摄像机位置不变,方向指向torso子树质心-->
<body name='torso' pos='0 0 1.4'>
<!—定义物体,名称为torso,位置在0 0 1.4-->
<camera name='tracking' pos='1 1 2' zaxis="1 2 3" mode='trackcom'/>
<!—摄像机名称tracking,位置在1 1 2-->
<!—确定局部z轴方向 1 2 3-->
<!—摄像机跟踪整个模型-->
<freejoint name="root"/>
<!—定义freejoint,名称为root-->
<geom name='torso1' type='capsule' fromto='0 -.07 0 0 .07 0' size='0.07'/>
<!—定义物体torsol,形状为胶囊状-->
<fromto由6个参数组成,前三个参数为一个点坐标,后三个参数为一个点坐标,胶囊装物体由前一个坐标指向后一个坐标>
<!—size指定圆柱部分半径-->
<geom name='head' type='sphere' pos='0 0 .19' size='.09'/>
<!—定义脑袋,球体,位置在0 0 0.19 球体半径为0.09-->
<geom name='uwaist' type='capsule' fromto='-.01 -.06 -.12 -.01 .06 -.12' size='0.06'/>
<!—定义腰,形状为胶囊装,方向由-0.01 -0.06 -0.12指向-0.01 0.06 -0.12-->
<!—圆柱半径为0.06-->
<body name='lwaist' pos='-.01 0 -0.260' quat='1.000 0 -0.002 0' >
<!—定义腰,位置在-0.01 0 -0.260-->
<!—方向由四元数1 0 -0.002 0定义,四元数前三个参数是欧拉角表示法,最后一个约束圆柱轴线方向的旋转-->
<geom name='lwaist' type='capsule' fromto='0 -.06 0 0 .06 0' size='0.06' />
<joint name='abdomen_z' type='hinge' pos='0 0 0.065' axis='0 0 1' range='-45 45' damping='5' stiffness='20' armature='0.02' />
<!—hinge创建了一个具有一个自由度的旋转铰链约束-->
<!—axis定义约束移动方向0 0 1-->
<!—range定义约束移动范围-45到45-->
<!—damping为阻尼相关系数-->
<!—stiffness如果这个参数是正数,会创建一个弹簧-->
<joint name='abdomen_y' type='hinge' pos='0 0 0.065' axis='0 1 0' range='-75 30' damping='5' stiffness='10' armature='0.02' />
<body name='pelvis' pos='0 0 -0.165' quat='1.000 0 -0.002 0' >
<joint name='abdomen_x' type='hinge' pos='0 0 0.1' axis='1 0 0' range='-35 35' damping='5' stiffness='10' armature='0.02' />
<geom name='butt' type='capsule' fromto='-.02 -.07 0 -.02 .07 0' size='0.09' />
<body name='right_thigh' pos='0 -0.1 -0.04' >
<joint name='right_hip_x' type='hinge' pos='0 0 0' axis='1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
<joint name='right_hip_z' type='hinge' pos='0 0 0' axis='0 0 1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
<joint name='right_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-120 20' damping='5' stiffness='20' armature='0.01' />
<geom name='right_thigh1' type='capsule' fromto='0 0 0 0 0.01 -.34' size='0.06' />
<body name='right_shin' pos='0 0.01 -0.403' >
<joint name='right_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' stiffness='1' armature='0.0060' />
<geom name='right_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
<body name='right_foot' pos='0 0 -.39' >
<joint name='right_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
<joint name='right_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
<geom name='right_foot_cap1' type='capsule' fromto='-.07 -0.02 0 0.14 -0.04 0' size='0.027' />
<geom name='right_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 0.02 0' size='0.027' />
</body>
</body>
</body>
<body name='left_thigh' pos='0 0.1 -0.04' >
<joint name='left_hip_x' type='hinge' pos='0 0 0' axis='-1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
<joint name='left_hip_z' type='hinge' pos='0 0 0' axis='0 0 -1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
<joint name='left_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-120 20' damping='5' stiffness='20' armature='0.01' />
<geom name='left_thigh1' type='capsule' fromto='0 0 0 0 -0.01 -.34' size='0.06' />
<body name='left_shin' pos='0 -0.01 -0.403' >
<joint name='left_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' stiffness='1' armature='0.0060' />
<geom name='left_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
<body name='left_foot' pos='0 0 -.39' >
<joint name='left_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
<joint name='left_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
<geom name='left_foot_cap1' type='capsule' fromto='-.07 0.02 0 0.14 0.04 0' size='0.027' />
<geom name='left_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 -0.02 0' size='0.027' />
</body>
</body>
</body>
</body>
</body>
<body name='right_upper_arm' pos='0 -0.17 0.06' >
<joint name='right_shoulder1' type='hinge' pos='0 0 0' axis='2 1 1' range='-85 60' stiffness='1' armature='0.0068' />
<joint name='right_shoulder2' type='hinge' pos='0 0 0' axis='0 -1 1' range='-85 60' stiffness='1' armature='0.0051' />
<geom name='right_uarm1' type='capsule' fromto='0 0 0 .16 -.16 -.16' size='0.04 0.16' />
<body name='right_lower_arm' pos='.18 -.18 -.18' >
<joint name='right_elbow' type='hinge' pos='0 0 0' axis='0 -1 1' range='-90 50' stiffness='0' armature='0.0028' />
<geom name='right_larm' type='capsule' fromto='0.01 0.01 0.01 .17 .17 .17' size='0.031' />
<geom name='right_hand' type='sphere' pos='.18 .18 .18' size='0.04'/>
</body>
</body>
<body name='left_upper_arm' pos='0 0.17 0.06' >
<joint name='left_shoulder1' type='hinge' pos='0 0 0' axis='2 -1 1' range='-60 85' stiffness='1' armature='0.0068' />
<joint name='left_shoulder2' type='hinge' pos='0 0 0' axis='0 1 1' range='-60 85' stiffness='1' armature='0.0051' />
<geom name='left_uarm1' type='capsule' fromto='0 0 0 .16 .16 -.16' size='0.04 0.16' />
<body name='left_lower_arm' pos='.18 .18 -.18' >
<joint name='left_elbow' type='hinge' pos='0 0 0' axis='0 -1 -1' range='-90 50' stiffness='0' armature='0.0028' />
<geom name='left_larm' type='capsule' fromto='0.01 -0.01 0.01 .17 -.17 .17' size='0.031' />
<geom name='left_hand' type='sphere' pos='.18 -.18 .18' size='0.04'/>
</body>
</body>
</body>
</worldbody>
<actuator>
<motor name='abdomen_y' gear='200' joint='abdomen_y' />
<motor name='abdomen_z' gear='200' joint='abdomen_z' />
<motor name='abdomen_x' gear='200' joint='abdomen_x' />
<motor name='right_hip_x' gear='200' joint='right_hip_x' />
<motor name='right_hip_z' gear='200' joint='right_hip_z' />
<motor name='right_hip_y' gear='600' joint='right_hip_y' />
<motor name='right_knee' gear='400' joint='right_knee' />
<motor name='right_ankle_x' gear='100' joint='right_ankle_x' />
<motor name='right_ankle_y' gear='100' joint='right_ankle_y' />
<motor name='left_hip_x' gear='200' joint='left_hip_x' />
<motor name='left_hip_z' gear='200' joint='left_hip_z' />
<motor name='left_hip_y' gear='600' joint='left_hip_y' />
<motor name='left_knee' gear='400' joint='left_knee' />
<motor name='left_ankle_x' gear='100' joint='left_ankle_x' />
<motor name='left_ankle_y' gear='100' joint='left_ankle_y' />
<motor name='right_shoulder1' gear='100' joint='right_shoulder1' />
<motor name='right_shoulder2' gear='100' joint='right_shoulder2' />
<motor name='right_elbow' gear='200' joint='right_elbow' />
<motor name='left_shoulder1' gear='100' joint='left_shoulder1' />
<motor name='left_shoulder2' gear='100' joint='left_shoulder2' />
<motor name='left_elbow' gear='200' joint='left_elbow' />
</actuator>
</mujoco>
参考mujoco官方文档:
https://mujoco.readthedocs.io/en/latest/XMLreference.html#body-inertial