-
Notifications
You must be signed in to change notification settings - Fork 1.1k
Description
Intro
Hi!
I am a researcher at the RAI Institute, I use MuJoCo for my research on whole body locomanipulation.
My setup
Ubuntu 22.04, Python. Mujoco 3.3.5
What's happening? What did you expect?
I am doing composing a scene with a tire and a ground. The tire has a visual and collision geometry. The first few times I construct my scene, the visual and collision geometries are aligned with each other

but after I create a few more copies of the the scene, they become misaligned

I would expect the behavior to be consistent regardless of how many copies of the scene I construct, so this is quite confusing to me. In addition, it seems the behavior is quite fragile and disappears when the code is changed in seemingly trivial ways (e.g., renaming a variable). I have documented some of these strange fixes in my code below.
Steps for reproduction
- Unzip the assets folder. It contains assets for a tire and a ground plane.
- Run the code below. It will create a scene with the tire and a ground plane, a display a static visualization.
- Close the visualization window. The code will then create a new copy of the scene and display another visualization.
- After closing the window a few times, you should see that the visual and collision geometries become misaligned.
Minimal model for reproduction
Assets
Code required for reproduction
# Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.
from dataclasses import dataclass
from pathlib import Path
from typing import Any
import mujoco
import mujoco.viewer
import numpy as np
from mujoco import MjData, MjModel
TIRE_RIM_ELEMENTS = {
"ground": "assets/ground/ground.xml",
"object": "assets/tire_rim/tire_rim.xml",
}
###############################################
########## Construction of the scene ##########
###############################################
def attach_body(body: mujoco.MjsBody, child_body: mujoco.MjsBody, name: str) -> None:
frame = body.add_frame()
prefix = f"{name}/"
frame.attach_body(child_body, prefix, "")
@dataclass
class ModelElement:
name: str
spec: mujoco.MjSpec
@property
def body(self) -> mujoco.MjsBody:
return self.spec.body(self.name)
@dataclass
class Scene:
elements: dict
def __post_init__(self) -> None:
self.spec = mujoco.MjSpec()
# This causes the problem
for element_prefix, element in self.elements.items():
element = self._load_element_from_path(element)
world_element_body = self.spec.body("world")
attach_body(world_element_body, element.body, element_prefix)
# Replacing the variable name from "element" to "element_path". This avoids the problem
# for element_prefix, element_path in self.elements.items():
# element = self._load_element_from_path(element_path)
# world_element_body = self.spec.body("world")
# attach_body(world_element_body, element.body, element_prefix)
# Assigning a variable to the element's body. This avoids the problem
# for element_prefix, element in self.elements.items():
# element = self._load_element_from_path(element)
# world_element_body = self.spec.body("world")
# element_body = element.spec.body(element.name)
# attach_body(world_element_body, element_body, element_prefix)
def _load_element_from_path(self, debug_element_path_raw: str) -> ModelElement:
debug_element_path = Path(debug_element_path_raw)
debug_name = debug_element_path.stem
debug_spec = mujoco.MjSpec().from_file(str(debug_element_path))
model_element = ModelElement(debug_name, debug_spec)
return model_element
def to_mj_model(self) -> Any:
model = self.spec.compile()
return model
########################################################
########## Initialize and visualize the scene ##########
########################################################
def make_scene() -> tuple[MjModel, MjData]:
scene = Scene(elements=TIRE_RIM_ELEMENTS)
model = scene.to_mj_model()
data = MjData(model)
# Set initial pose
reset_pose = np.array(
[
0,
0,
0.275,
1.0,
0.0,
0.0,
0.0,
]
)
data.qpos = reset_pose
data.qvel = np.zeros_like(data.qvel)
mujoco.mj_forward(model, data)
return model, data
def main() -> None:
# Need to create a few scenes to trigger the problem
for _ in range(10):
model, data = make_scene()
# Visualize
with mujoco.viewer.launch_passive(model, data) as viewer:
while viewer.is_running():
viewer.sync()
if __name__ == "__main__":
main()
Confirmations
- I searched the latest documentation thoroughly before posting.
- I searched previous Issues and Discussions, I am certain this has not been raised before.