Skip to content

Inconsistent behaviour of Site (quat, pos) dependent on initialization #3029

@schlexl

Description

@schlexl

Intro

Hi!

I am currently using sites as lightweight visualization markers (e.g., for robot traces), the site pose is edited at runtime by writing to model.site("...").pos `` / model.site("...").quat and then calling mujoco.mj_forward(model, data)```.

Observed behavior seems to depend on how the site is initialized in XML:

  • If initialized with a non-zero position and a non-identity quaternion, then runtime edits appear to propagate to mjData and are visible in the passive viewer.

  • If initialized with zero position (or omitted/default) or an identity quaternion, then runtime edits appear to not propagate to mjData and the site can appear static in the launch_passive viewer.

My setup

I currently run Mujoco v3.4.0, as far as I tested this feature worked last at v2.3.7 (atleast for the quaternion)
Ubuntu 22.04.5 LTS
Bindings: mujoco

What's happening? What did you expect?

When setting
model.site("...").pos[2]` = 0.1
or
model.site("...").quat = np.array([0.70710678, 0., 0.70710678, 0.])
i expect the passive viewer, as well as the data.site("...").xpos or data.site("...").xmat
renders as the new site position and orientation and also be updated in the data.
This behaviour works, dependent on the initialization of the Site. See reproduction code.

Steps for reproduction

Position bug minimal example:
If I initialize the Site with pos="0.01 0 0." the behavior is as expected.
If I initialize the Site with pos="0.0 0 0." the behavior is different and not as expected.
The same applies to quats.

import mujoco
import numpy as np
from mujoco.viewer import launch_passive
##This works""
xml_test = """
<mujoco model="test">
  <compiler angle="radian" meshdir="environment_parts/" texturedir="environment_parts/" />

  <worldbody>
  <light name="top" pos="0 0 2" mode="trackcom"/>
  <site name="boye_COM" pos="0.01 0 0." size="0.01" rgba="1 0 0 1"/>
  <geom name="floor" type="plane" pos="0 0 0" size="5 5 0.01" rgba="0.8 0.8 0.8 1" /> 
  </worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml_test)
data = mujoco.MjData(model)
model.site("boye_COM").pos[2] = 0.1
mujoco.mj_forward(model, data)
assert np.all(data.site("boye_COM").xpos == model.site("boye_COM").pos)
#This does not###
xml_test = """
<mujoco model="test">
  <compiler angle="radian" meshdir="environment_parts/" texturedir="environment_parts/" />

  <worldbody>
  <light name="top" pos="0 0 2" mode="trackcom"/>
  <site name="boye_COM" pos="0.0 0 0." size="0.01" rgba="1 0 0 1"/>
  <geom name="floor" type="plane" pos="0 0 0" size="5 5 0.01" rgba="0.8 0.8 0.8 1" /> 
  </worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml_test)
data = mujoco.MjData(model)
model.site("boye_COM").pos[2] = 0.1
mujoco.mj_forward(model, data)
assert np.all(data.site("boye_COM").xpos == model.site("boye_COM").pos)

And minimal example for quat bug

import mujoco
import numpy as np
from mujoco.viewer import launch_passive
from scipy.spatial.transform import Rotation
##This works""
xml_test = """
<mujoco model="test">
  <compiler angle="radian" meshdir="environment_parts/" texturedir="environment_parts/" />

  <worldbody>
  <light name="top" pos="0 0 2" mode="trackcom"/>
  <site name="boye_COM" pos="0.01 0 0." size="0.01" rgba="1 0 0 1" quat=" 0.70710678 0. 0.70710678 0." />
  <geom name="floor" type="plane" pos="0 0 0" size="5 5 0.01" rgba="0.8 0.8 0.8 1" /> 
  </worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml_test)
data = mujoco.MjData(model)
model.site("boye_COM").quat = np.array([1., 0.0 ,0.0, 0.])
mujoco.mj_forward(model, data)
quat_data = Rotation.from_matrix(data.site("boye_COM").xmat.reshape(3,3)).as_quat(scalar_first=True)
assert np.allclose(
    quat_data,
    model.site("boye_COM").quat,
    rtol=1e-6,
    atol=1e-8,
)

### This does not###
xml_test = """
<mujoco model="test">
  <compiler angle="radian" meshdir="environment_parts/" texturedir="environment_parts/" />

  <worldbody>
  <light name="top" pos="0 0 2" mode="trackcom"/>
  <site name="boye_COM" pos="0.01 0 0." size="0.01" rgba="1 0 0 1" quat="1. 0 0 0 "/>
  <geom name="floor" type="plane" pos="0 0 0" size="5 5 0.01" rgba="0.8 0.8 0.8 1" /> 
  </worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml_test)
data = mujoco.MjData(model)
model.site("boye_COM").quat = np.array([0.70710678, 0., 0.70710678, 0.])
mujoco.mj_forward(model, data)
quat_data = Rotation.from_matrix(data.site("boye_COM").xmat.reshape(3,3)).as_quat(scalar_first=True)
assert np.allclose(
    quat_data,
    model.site("boye_COM").quat,
    rtol=1e-6,
    atol=1e-8,
)

I also added them as files:
bug_quat.py

zero_init_site_bug.py

Minimal model for reproduction

No response

Code required for reproduction

No response

Confirmations

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions