mujoco icon indicating copy to clipboard operation
mujoco copied to clipboard

`mj_step` uses the plugin config of the `MjData` instead of `MjModel`

Open milutter opened this issue 6 months ago • 5 comments

Summary

The function mj_step(model, data) uses the plugin config from the the model that is used to create the data struct and ignores the plugin config from the model. For example mj_step(model_a, mjData(model_b)) uses the plugin config of model_b which was used to instantiate the MjData struct while it should be using the plugin config of model_a.

From @quagla The plugin is created only during the creation of mjData, which stores the pointer to it so, although the attributes are in mjModel, the plugin reads them once from the mjModel used in mjData, producing the behavior you observed [code]. A quick solution would be to read the attributes again every time Compute() is called. The other solution is to move the plugin pointer to mjModel, which I've tried this morning but I haven't succeeded so far (if possible at all, because there are a few assumptions about having mjData available in the plugin constructor).

My setup

OS: Ubuntu 22.04 MuJoCo version: 3.3.2 API: Python

Minimal Example

# Third Party
import mujoco
import numpy as np

XML_MODEL_A = """
<mujoco>
  <extension>
    <plugin plugin="mujoco.pid">
      <instance name="pid">
        <config key="kp" value="40.0"/>
        <config key="ki" value="40"/>
        <config key="kd" value="4"/>
        <config key="slewmax" value="3" />
        <config key="imax" value="1"/>
      </instance>
    </plugin>
  </extension>

  <worldbody>
    <body>
      <joint name="j" type="slide" axis="0 0 1" />
      <geom size="0.01" mass="1"/>
    </body>
  </worldbody>

  <actuator>
    <plugin joint="j" plugin="mujoco.pid" instance="pid" actdim="2"/>
  </actuator>
</mujoco>
"""

XML_MODEL_B = """
<mujoco>
  <extension>
    <plugin plugin="mujoco.pid">
      <instance name="pid">
        <config key="kp" value="0.0"/>
        <config key="ki" value="0.1"/>
        <config key="kd" value="0.1"/>
        <config key="slewmax" value="3" />
        <config key="imax" value="1"/>
      </instance>
    </plugin>
  </extension>

  <worldbody>
    <body>
      <joint name="j" type="slide" axis="0 0 1" />
      <geom size="0.01" mass="1"/>
    </body>
  </worldbody>

  <actuator>
    <plugin joint="j" plugin="mujoco.pid" instance="pid" actdim="2"/>
  </actuator>
</mujoco>
"""


def test_pid_plugin() -> None:
    """Test the PID plugin."""
    # Matching Pairs of MjModel and MjData

    # Case 1: Model A & Model A => Force = 40.0
    expected_force = 40.0

    model = mujoco.MjModel.from_xml_string(XML_MODEL_A)
    data = mujoco.MjData(mujoco.MjModel.from_xml_string(XML_MODEL_A))
    data.ctrl[0] = 1.0

    mujoco.mj_step(model, data)
    np.testing.assert_allclose(data.actuator_force[0], expected_force, atol=0.1)

    # Case 2: Model B & Model B => Force = 0.0
    expected_force = 0.0

    model = mujoco.MjModel.from_xml_string(XML_MODEL_B)
    data = mujoco.MjData(mujoco.MjModel.from_xml_string(XML_MODEL_B))
    data.ctrl[0] = 1.0

    mujoco.mj_step(model, data)
    np.testing.assert_allclose(data.actuator_force[0], expected_force, atol=0.1)

    # Mismatching Pairs of MjModel and MjData
    # Case 3: Model A & Model B => Force = 40.0
    expected_force = 0.0 # THIS SHOULD BE 40.0

    model = mujoco.MjModel.from_xml_string(XML_MODEL_A)
    data = mujoco.MjData(mujoco.MjModel.from_xml_string(XML_MODEL_B))
    data.ctrl[0] = 1.0

    mujoco.mj_step(model, data)
    np.testing.assert_allclose(data.actuator_force[0], expected_force, atol=0.1)

    # Case 4: Model B & Model A => Force = 0.0
    expected_force = 40.0 # THIS SHOULD BE 0.0

    model = mujoco.MjModel.from_xml_string(XML_MODEL_B)
    data = mujoco.MjData(mujoco.MjModel.from_xml_string(XML_MODEL_A))
    data.ctrl[0] = 1.0

    mujoco.mj_step(model, data)
    np.testing.assert_allclose(data.actuator_force[0], expected_force, atol=0.1)

Confirmations

milutter avatar May 21 '25 13:05 milutter

I don't think that moving the plugin to the model is a good idea. Imagine that you create many mjDatas from a model and step them all (maybe multithreaded). The plugin instance might carry state or cached values, and existing plugins were not written to handle being used from multiple threads or mjData instances.

Maybe we could read plugin config and recreate the plugin on mj_resetData. Thoughts?

nimrod-gileadi avatar May 23 '25 12:05 nimrod-gileadi

I had some more time to think about @quagla suggestion of reading the config values from MjModel within the compute function. As far as I understand his suggestion, one would move the following code from the FromModel function to the Compute function. For example the PID plugin. [code]

  config.p_gain = ReadOptionalDoubleAttr(m, instance, kAttrPGain).value_or(0);
  config.i_gain = ReadOptionalDoubleAttr(m, instance, kAttrIGain).value_or(0);
  config.d_gain = ReadOptionalDoubleAttr(m, instance, kAttrDGain).value_or(0);

to read the config values at each function call. I like this approach, but I have a question regarding performance:

  • Would this implementation affect the plugin performance?
  • How expensive is the ReadOptionalDoubleAttr function?

The benefit of this approach would be that no code change would be required. One would only need to add more documentation and change the examples as most people are pattern matching the examples. One could potentially introduce the concept of static parameters which are read in the function FromModel and varying parameters which are always read in the Compute function.

What is you opinion on this? @nimrod-gileadi

milutter avatar May 29 '25 18:05 milutter

It's all string based, so performance is probably not optimal. I don't have a sense though about the impact. What do you think about @nimrod-gileadi suggestion of recreating the plugin on mj_resetData?

quagla avatar Jun 02 '25 08:06 quagla

I don't fully understand what recreating on mj_resetData means and how performant would this be. I am mainly thinking about mujoco.rollout where one passes 4096 different states and MjModel where each model could potentially have different plugin parameter. Could you elaborate on that option and how it would affect the performance of rollout when a lot of different models are used?

I am also thinking about overloading existing parameters in the MjModel. For example I should be able to store gains in the biasprm and gainprm values of the actuators which are linked to the actuator plugin. Another approach would be using the actuator user data which is numeric and would not need the string look-up, i.e., mjtNum* actuator_user;?

milutter avatar Jun 07 '25 21:06 milutter

@nimrod-gileadi's idea would not work for mujoco.rollout since resetData is not called there.

actuator_user is a great idea and I think the correct solution. We discourage using it when you want to make your plugin code public, since who knows what a third party did, but since this is your own internal code (right?), the _user fields are exactly what you need.

@nimrod-gileadi @quagla, do you agree? Or am I missing something?

yuvaltassa avatar Jun 08 '25 06:06 yuvaltassa

@milutter is this issue resolved for you? Can I close it?

yuvaltassa avatar Aug 18 '25 12:08 yuvaltassa