mujoco icon indicating copy to clipboard operation
mujoco copied to clipboard

Failed to load model after setting user actuator callback

Open yushijinhun opened this issue 10 months ago • 4 comments

Description

Loading a model with user actuators (using mujoco.MjModel.from_xml_path) would fail if a user actuator callback is set (using mujoco.set_mjcb_act_dyn, set_mjcb_act_gain, or set_mjcb_act_bias).

To reproduce the problem:

import mujoco

def my_act_dyn(model, data, id):
	return 0.0

mujoco.set_mjcb_act_dyn(my_act_dyn)

model = mujoco.MjModel.from_xml_path("user_act.xml")

user_act.xml:

<mujoco>
	<worldbody>
		<body>
			<inertial pos="0 0 0" mass="1.0" diaginertia="1.0 1.0 1.0" />
			<joint name="my_joint" />
		</body>
	</worldbody>
	<actuator>
		<general dyntype="user" joint="my_joint" />
	</actuator>
</mujoco>

Output:

Traceback (most recent call last):
  File "/home/yushijinhun/robodev/mujoco_act_bug/user_act.py", line 8, in <module>
    model = mujoco.MjModel.from_xml_path("user_act.xml")
            ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
ValueError: Error: engine error: Python exception raised

I tried to debug this problem using GDB and here is the backtrace:

#0  mujoco::python::(anonymous namespace)::EscapeWithPythonException () at /tmp/pip-req-build-gqttshg5/mujoco/callbacks.cc:36
#1  0x00007ffff6fa0210 in mujoco::python::(anonymous namespace)::MjWrapperLookup<mjData_> (ptr=0x12d2e00) at /tmp/pip-req-build-gqttshg5/mujoco/callbacks.cc:117
#2  0x00007ffff6fa1195 in mujoco::python::(anonymous namespace)::MjWrapperLookup<mjData_> (ptr=0x12d2e00) at /tmp/pip-req-build-gqttshg5/mujoco/callbacks.cc:122
#3  0x00007ffff6f99ae3 in mujoco::python::(anonymous namespace)::PyMjcbActDyn (m=0x12c95c0, d=0x12d2e00, id=0) at /tmp/pip-req-build-gqttshg5/mujoco/callbacks.cc:208
#4  0x00007ffff6b14e64 in mj_fwdActuation (m=0x12c95c0, d=0x12d2e00) at /home/yushijinhun/repos/mujoco/src/engine/engine_forward.c:257
#5  0x00007ffff6b17569 in mj_forwardSkip (m=0x12c95c0, d=0x12d2e00, skipstage=0, skipsensor=0) at /home/yushijinhun/repos/mujoco/src/engine/engine_forward.c:851
#6  0x00007ffff6b1763f in mj_forward (m=0x12c95c0, d=0x12d2e00) at /home/yushijinhun/repos/mujoco/src/engine/engine_forward.c:865
#7  0x00007ffff6b176cb in mj_step (m=0x12c95c0, d=0x12d2e00) at /home/yushijinhun/repos/mujoco/src/engine/engine_forward.c:877
#8  0x00007ffff6d557f5 in mjCModel::TryCompile (this=0x12c4110, m=@0x7fffffffb128: 0x12c95c0, d=@0x7fffffffb130: 0x12d2e00, vfs_provider=0) at /home/yushijinhun/repos/mujoco/src/user/user_model.cc:2854
#9  0x00007ffff6d51dad in mjCModel::Compile (this=0x12c4110, vfs_provider=0) at /home/yushijinhun/repos/mujoco/src/user/user_model.cc:2442
#10 0x00007ffff6d9cd86 in _loadXML (filename=0x7fffffffd1a0 "user_act.xml", vfs_provider=0, error=0x7fffffffba30 "", error_sz=1024) at /home/yushijinhun/repos/mujoco/src/xml/xml_api.cc:86
#11 0x00007ffff6d9cf2a in mj_loadXML (filename=0x7fffffffd1a0 "user_act.xml", vfs=0x0, error=0x7fffffffba30 "", error_sz=1024) at /home/yushijinhun/repos/mujoco/src/xml/xml_api.cc:116

It seems that MuJoCo creates a temporary mjData struct and does simulation during model compilation. The simulation calls mjcb_act_dyn to calculate activation dynamics. Because the callback function is in Python, the mjData has to be wrapped before passing to Python code. However, that temporary mjData struct has never been passed to MjWrapper's constructor to create such wrapper. Therefore, the lookup of the corresponding wrapper object of the mjData struct would fail.

Environment

  • Operating system: Ubuntu 23.10 (devel) / Linux 6.3.0
  • MuJoCo version: 2.3.8 (built from source, commit: https://github.com/deepmind/mujoco/commit/93012bf16420d190fdf2e7bbe59e28d128b302f7)
  • Python binding: mujoco (Python 3.11.4)

yushijinhun avatar Aug 09 '23 13:08 yushijinhun

The callbacks are tested in bindings_test.py. Can you please inspect how they are used in the tests and see if that resolves your problem?

yuvaltassa avatar Aug 14 '23 11:08 yuvaltassa

@yuvaltassa Thanks for highlighting this. I've noticed that it's essential to unset all callbacks before invoking mujoco.MjModel.from_xml_string or from_xml_path, as demonstrated in bindings_test.py.

Is this the intended behavior? Some documentation on this aspect might be beneficial for clarity.

yushijinhun avatar Aug 14 '23 13:08 yushijinhun

Your analysis is correct. @yuvaltassa maybe we should just disable all callbacks during TryCompile?

saran-t avatar Aug 25 '23 15:08 saran-t

Yup sounds sensible. It's hard to imagine a callback that would be required for TryCompile (with the exception of truly obscene things that shouldn't be done anyway)

yuvaltassa avatar Aug 25 '23 16:08 yuvaltassa