google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
7.47k stars 734 forks source link

Saving the xml with updates after mj_step #1719

Closed budzianowski closed 2 weeks ago

budzianowski commented 3 weeks ago

Is your feature request related to a problem? Please describe. Hey, I'm running the following code:

import mujoco path = "model.xml" mj_model = mujoco.MjModel.from_xml_path(path) mj_model.opt.solver = mujoco.mjtSolver.mjSOL_CG mj_model.opt.iterations = 6 data = mujoco.MjData(mj_model) data.qpos = new_qpos # some new position mujoco.mj_step(mj_model, data) mujoco.mj_saveLastXML("new_model.xml", mj_model)

Describe the solution you'd like I would like to save the new xml with updated body positions (and geoms) after the mj_step.

Describe alternatives you've considered I'm not sure if there is anything smarter right now than to log all the bodies and geoms pos and quat and save it to the xml file?

yuvaltassa commented 2 weeks ago

That's what keyframes are for, but we should really expose an API function to do what simulate does here...

To be clear this will not change the base configuration, but it will save the state to the model and then after mk_saveXML it will appear in the XML and you'll be able to reload it.

LilianLaporte commented 2 weeks ago

I tried using the keyframes that you suggested here but I got a problem. If I use it in the same way, I get this error `TypeError: mju_copy(): incompatible function arguments. The following argument types are supported:

  1. (res: numpy.ndarray[numpy.float64[m, 1], flags.writeable], vec: numpy.ndarray[numpy.float64[m, 1]]) -> None`. It comes from 2 problems:
    • apparently there should not be 3 parameters to the function but 2 (which is incompatible with the documentation)
    • the shape of the data is wrong (e.g. m.key_qpos: (1,27) & d.qpos: (27,))

I end up with a code (withtout errors) like this:

mujoco.mju_copy(m.key_qpos.T, np.expand_dims(d.qpos, axis=1))
mujoco.mju_copy(m.key_qvel.T, d.qvel)
mujoco.mju_copy(m.key_act.T, d.act)
mujoco.mju_copy(m.key_mpos.T, d.mocap_pos.T)
mujoco.mju_copy(m.key_mquat.T, d.mocap_quat.T)
mujoco.mju_copy(m.key_ctrl.T, d.ctrl)

On top of that, the model m is not updated, like if the copy did not work.

Note: I am working with the following xml file:

Details

```xml ```