keyframe
keyframe 用于定义模型在特定时间点的状态,包括关节的位置和速度。
对于freejoint 设置qpos
七个值,前三个值表示位置,后四个值表示四元数姿态。
<mujoco model="robot_arm">
<compiler angle="degree"/>
<option timestep="0.001"/>
<asset>
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072" />
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4"
rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance="0.2" />
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.01" type="plane" material="groundplane"/>
<!-- 定义基座体 -->
<body name="base" pos="0 0 0.1">
<geom name="base_geom" type="box" size="0.2 0.2 0.1" rgba="1 0 0 1"/>
<freejoint />
</body>
</worldbody>
<keyframe>
<!-- 定义初始关键帧 -->
<key name="home" qpos="0 0 0 0 0 0 0"/>
</keyframe>
</mujoco>
对于joint,类型为hinge(默认值),设置qpos
一个值,表示角度/弧度
<mujoco model="robot_arm">
<compiler angle="degree"/>
<option timestep="0.001"/>
<asset>
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072" />
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4"
rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance="0.2" />
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.01" type="plane" material="groundplane"/>
<!-- 定义基座体 -->
<body name="base" pos="0 0 0.1">
<geom name="base_geom" type="box" size="0.2 0.2 0.1" rgba="1 0 0 1"/>
<freejoint />
<!-- 定义上臂体 -->
<body name="upper_arm" pos="0 0 0.1">
<!-- 上臂与基座之间的关节 -->
<joint name="shoulder_joint" type="hinge" axis="0 1 0" range="-90 90"/>
<geom name="upper_arm_geom" type="capsule" fromto="0 0 0 0 0 0.3" size="0.05" rgba="0 1 0 1"/>
</body>
</body>
</worldbody>
<keyframe>
<!-- 定义初始关键帧 -->
<key name="home" qpos="0 0 0 0 0 0 0 30"/>
</keyframe>
</mujoco>
对于ball,类型为box,设置qpos
四个值,关节的初始姿态,分别对应四元数的四个分量(w, x, y, z)
<mujoco model="robot_arm">
<compiler angle="degree"/>
<option timestep="0.001"/>
<asset>
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072" />
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4"
rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance="0.2" />
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.01" type="plane" material="groundplane"/>
<!-- 定义基座体 -->
<body name="base" pos="0 0 0.1">
<geom name="base_geom" type="box" size="0.2 0.2 0.1" rgba="1 0 0 1"/>
<freejoint />
<!-- 定义上臂体 -->
<body name="upper_arm" pos="0 0 0.1">
<!-- 上臂与基座之间的关节 -->
<joint name="ball_joint" type="ball"/>
<geom name="arm_geom" type="capsule" fromto="0 0 0 0 0 0.3" size="0.05" rgba="0 1 0 1"/>
</body>
</body>
</worldbody>
<keyframe>
<!-- 定义初始关键帧 -->
<key name="home" qpos="0 0 0 0 0 0 0 1 0 0 0"/>
</keyframe>
</mujoco>
对于ball,类型为slide,设置qpos
一个值,关节的位置
<mujoco model="robot_arm">
<compiler angle="degree"/>
<option timestep="0.001"/>
<asset>
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072" />
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4"
rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance="0.2" />
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.01" type="plane" material="groundplane"/>
<!-- 定义基座体 -->
<body name="base" pos="0 0 0.1">
<geom name="base_geom" type="box" size="0.2 0.2 0.1" rgba="1 0 0 1"/>
<freejoint />
<!-- 定义上臂体 -->
<body name="upper_arm" pos="0 0 0.1">
<!-- 上臂与基座之间的关节 -->
<joint name="slide_joint" type="slide"/>
<geom name="arm_geom" type="capsule" fromto="0 0 0 0 0 0.3" size="0.05" rgba="0 1 0 1"/>
</body>
</body>
</worldbody>
<keyframe>
<!-- 定义初始关键帧 -->
<key name="home" qpos="0 0 0 0 0 0 0 0.1"/>
</keyframe>
</mujoco>