Skip to content

mj_step uses the plugin config of the MjData instead of MjModel #2644

Open
@milutter

Description

@milutter

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

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