How to define a keyframe for joints in bodies that are being replicated? #2360
-
IntroHello, I'm a graduate student and use MuJoCo for my research on robotics. My setupMuJoCo version 3.2.6 (python - MacOS 15.2, arm architecture (apple M3 chip) My questionI am trying to spawn two of the same robot arm into a scene for bimanual manipulation. I plan to do this via the replicate tag. I would like to specify a keyframe so that I can initialize both robot arms to a pre-defined "home" joint configuration. However, it seems like The xml below gives a minimal example of a body with 1 DOF. I spawn two bodies with
I would like to take approach number 2 above, since I know I'll have two joints and want to have values defined for each joint. However, when I try both approach 1 and 2 listed above, I get the following behavior:
For this simple example, how can I achieve a keyframe with Also, I am a little surprised that when using replicate for this example, I can define a keyframe with a Minimal model and/or code that explain my questionIf you encountered the issue in a complex model, please simplify it as much as possible (while still reproducing the issue). Model: minimal XML<mujoco model="2 balls translating along xy-plane">
<worldbody>
<replicate count="2" offset="0 1 0">
<body name="ball" pos="0 0 1">
<joint name="ball_slide_x" type="slide" axis="1 0 0" range="-2 2"/>
<geom type="sphere" size="0.1" rgba="0 1 0 1"/>
</body>
</replicate>
</worldbody>
<keyframe>
<!--
Can also change the keyframe to the following, and then run the code snippet below (behavior doesn't change):
<key name="home" qpos="0.5"/>
-->
<key name="home" qpos="0.5 0.25"/>
</keyframe>
</mujoco>
Code: import mujoco
model = mujoco.MjModel.from_xml_string(xml)
# I would like this to be what's defined in the xml: [0.5, 0.25]
print(model.keyframe('home').qpos)
# I assume these are added as an artifact of using `replicate`?
print(model.keyframe('home0').qpos)
print(model.keyframe('home1').qpos) Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 2 comments 2 replies
-
Hi, yes you have to set it programmatically. And yes, the fact that you can load a keyframe of size 2 sounds like a bug. There are a few examples here https://github.com/google-deepmind/mujoco/blob/main/test/user/user_api_test.cc (look in particular at AttachSame) of the intended behavior of keyframes with attach (replicate is a self-attach). |
Beta Was this translation helpful? Give feedback.
-
Thanks, I am able to achieve what I want programmatically by using the following xml file (I removed the Model: manual keyframe allocation xml<mujoco model="Ball translating along xy-plane">
<!-- Reserve space for a "home" keyframe -->
<size nkey="1"/>
<worldbody>
<replicate count="2" offset="0 1 0">
<body name="ball" pos="0 0 1">
<joint name="ball_slide_x" type="slide" axis="1 0 0" range="-2 2"/>
<geom type="sphere" size="0.1" rgba="0 1 0 1"/>
</body>
</replicate>
</worldbody>
</mujoco>
Code: import mujoco
model = mujoco.MjModel.from_xml_string(xml)
data = mujoco.MjData(model)
print(data.qpos) # should print [0, 0]
model.key_qpos[0] = np.array([0.5, 0.25])
mujoco.mj_resetDataKeyframe(model, data, 0)
print(data.qpos) # should print [0.5, 0.25] This approach has the following limitations
I can work around these limitations for now with helper python code/configuration files/etc. Let me know if there's a better way to programmatically set/use keyframes than what I outlined here.
Here's a simpler model file that shows a potential bug with replicate/keyframe sizes: Model: buggy replicate keyframe xml<mujoco model="Test replicate and keyframe sizes">
<worldbody>
<replicate count="1" offset="0 1 0">
<body name="ball" pos="0 0 1">
<geom type="sphere" size="0.1"/>
</body>
</replicate>
</worldbody>
<keyframe>
<!-- this should not work since the model has no joints! -->
<key name="home" qpos="0.5 0.25"/>
</keyframe>
</mujoco>
The model loads without errors if
Would you like me to submit a bug report as a separate issue for this? |
Beta Was this translation helpful? Give feedback.
Thanks, I am able to achieve what I want programmatically by using the following xml file (I removed the
<keyframe>
section and added<size nkey="1"/>
to manually reserve one keyframe) and python code:Model:
manual keyframe allocation xml
Code: