整体示例
<mujoco model="example">
<include file="h1.xml" />
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0" />
<rgba haze="0.15 0.25 0.35 1" />
<global azimuth="-140" elevation="-30" />
</visual>
<!-- set some defaults for units and lighting -->
<compiler angle="radian" meshdir="meshes"/>
<!-- define default value -->
<default>
<joint limited="true" damping="1" armature="0"/>
<geom condim="1" material="matgeom"/>
<motor ctrlrange="-.4 .4" ctrllimited="true"/>
</default>
<!-- import our stl files -->
<asset>
<mesh file="base.STL" />
<mesh file="link1.STL" />
<mesh file="link2.STL" />
</asset>
<!-- define our robot model -->
<worldbody>
<!-- set up a light pointing down on the robot -->
<light directional="true" pos="-0.5 0.5 3" dir="0 0 -1" />
<!-- add a floor so we don't stare off into the abyss -->
<geom name="floor" pos="0 0 0" size="1 1 1" type="plane" rgba="1 0.83 0.61 0.5"/>
<!-- the ABR Control Mujoco interface expects a hand mocap -->
<body name="hand" pos="0 0 0" mocap="true">
<geom type="box" size=".01 .02 .03" rgba="0 .9 0 .5" contype="2"/>
</body>
<!-- start building our model -->
<body name="base" pos="0 0 0">
<geom name="link0" type="mesh" mesh="base" pos="0 0 0"/>
<inertial pos="0 0 0" mass="0" diaginertia="0 0 0"/>
<!-- nest each child piece inside the parent body tags -->
<body name="link1" pos="0 0 1">
<!-- this joint connects link1 to the base -->
<joint name="joint0" axis="0 0 1" pos="0 0 0"/>
<geom name="link1" type="mesh" mesh="link1" pos="0 0 0" euler="0 3.14 0"/>
<inertial pos="0 0 0" mass="0.75" diaginertia="1 1 1"/>
<body name="link2" pos="0 0 1">
<!-- this joint connects link2 to link1 -->
<joint name="joint1" axis="0 0 1" pos="0 0 0"/>
<geom name="link2" type="mesh" mesh="link2" pos="0 0 0" euler="0 3.14 0"/>
<inertial pos="0 0 0" mass="0.75" diaginertia="1 1 1"/>
<!-- the ABR Control Mujoco interface uses the EE body to -->
<!-- identify the end-effector point to control with OSC-->
<body name="EE" pos="0 0.2 0.2">
<inertial pos="0 0 0" mass="0" diaginertia="0 0 0" />
</body>
</body>
</body>
</body>
</worldbody>
<!-- attach actuators to joints -->
<actuator>
<motor name="joint0_motor" joint="joint0"/>
<motor name="joint1_motor" joint="joint1"/>
</actuator>
<keyframe>
<key name="home" qpos="
0 0 0.98
1 0 0 0
0 0 -0.4 0.8 -0.4
0 0 -0.4 0.8 -0.4
0
0 0 0 0
0 0 0 0
0"/>
</keyframe>
</mujoco>
一级主要节点
官方查询位置:https://mujoco.readthedocs.io/en/stable/XMLreference.html
mujoco
全局根节点,只能有一个
include
导入另一个xml文件
visual
视觉效果
map
:定义了雾化效果的参数,包括起始和结束位置以及力度。quality
:设置了阴影和抗锯齿的参数。headlight
:设置了头灯的参数,包括漫反射、环境光和高光。rgba
:设置了雾化效果的颜色。global
:设置了全局光照的方向。
compiler
编译器选项,用于设置模型的编译参数。
angle="radian"
:角度单位设置为弧度。inertiafromgeom="auto"
:惯性矩从几何体自动计算。inertiagrouprange="4 5"
:定义了惯性矩计算的组范围。
default
设置模型中各种节点的默认属性
asset
定义仿真环境中使用的资源,如纹理和材料
worldbody
模型的世界部分,定义了模拟环境中的物体、光源和相机等元素
actuator
定义了动作控制器,用于控制机器人的手指关节的运动
keyframe
指定了各个关节的初始位置信息
二级主要节点
joint
定义父子body之间的关节
name
:关节的名称。pos
:关节的位置。axis
:关节的旋转轴。limited="true"
:表示关节是否有限制。range
:关节的运动范围。frictionloss
:关节的摩擦损失。
geom
几何形状
quat
:指定了几何体的旋转四元数。type="mesh"
:指定了几何体的类型为网格。mesh
:指定了该几何体所使用的网格模型。rgba
:指定了几何体的颜色。
motor
电机
ctrlrange
:为电机设置了机输出力矩的最小和最大值。ctrllimited
:电机控制是有限制,即电机输出将被限制在上面指定的ctrlrange
内。
light
灯光,设置类型、漫反射和高光等参数
body
物体,值得注意的是,body可以嵌套。默认情况下,父body下的所有子body是固定到父body的,即父子一起运动。
inertial
惯性,设置物体的质量和惯性张量等