find_geom for Model Editing Python API to update size dynamically #2295
-
IntroHi! I am a PhD student at BYU, I use MuJoCo for my research on robotic manipulation. My setupMuJoCo v3.2.3, Ubuntu 20.04, Python API My questionI've been working on implementing methods to dynamically update an object's size (i.e. in between episodes of reinforcement learning training). I've had lots of odd contact behavior attempting to dynamically update size. Below is a MWE of what I was attempting to do--and a video of the resulting behavior: weird_mujoco_behavior.mp4I expected the box to just sit on the ground plane, but instead if penetrates and bounces around randomly. Why does this happen? What am I missing? I've read through related Github issues (e.g. #453) and it seems that the recommended way to approach this is the new Model Editing API via mjSpec. That's great, as it does seem to solve the above bouncing issues. The box size changes correctly and the box just sits on the ground plane. MWE with mjSpec: import mujoco as mj
import mujoco.viewer as viewer
import time
xml_string = """
<?xml version="1.0"?>
<mujoco model="box_on_ground">
<!-- Worldbody -->
<worldbody>
<!-- Ground plane -->
<geom name="ground" type="plane" pos="0 0 0" size="5 5 0.1" rgba="0.7 0.7 0.7 1" />
<!-- Box -->
<body name="box" pos="0 0 0">
<geom name="box_geom" type="box" size="0.05 0.05 0.05" rgba="1 0 0 1" />
<freejoint name="free" />
</body>
</worldbody>
</mujoco>
"""
mjspec = mj.MjSpec()
mjspec.from_string(xml_string)
box = mjspec.find_body("box")
box_geom = box.first_geom()
box_geom.size = [1 / 2, 1 / 2, 1 / 2]
model = mjspec.compile()
data = mj.MjData(model)
#still place object on the ground
data.joint("free").qpos[:3] = [0, 0, 1 / 2]
with viewer.launch_passive(model, data) as viewer:
viewer.sync()
input()
while viewer.is_running():
step_start = time.time()
mj.mj_step(model, data)
viewer.sync()
time_until_next_step = model.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step) The only way I could figure out how to access the geom to change its size was via My question here is this: Is there a more direct way of accessing geoms through the model editing API that avoids looping through items using Minimal model and/or code that explain my questionimport mujoco as mj
import mujoco.viewer as viewer
import time
xml_string = """
<mujoco model="box_on_ground">
<!-- Worldbody -->
<worldbody>
<!-- Ground plane -->
<geom name="ground" type="plane" pos="0 0 0" size="5 5 0.1" rgba="0.7 0.7 0.7 1" />
<!-- Box -->
<body name="box" pos="0 0 0">
<geom name="box_geom" type="box" size="0.05 0.05 0.05" rgba="1 0 0 1" />
<freejoint name="free" />
</body>
</worldbody>
</mujoco>
"""
model = mj.MjModel.from_xml_string(xml_string)
data = mj.MjData(model)
#update box geom size
model.geom("box_geom").size = [1 / 2, 1 / 2, 1 / 2]
#update joint position in qpos to set box on ground
data.joint("free").qpos[:3] = [0, 0, 1 / 2]
with viewer.launch_passive(model, data) as viewer:
viewer.sync()
input()
while viewer.is_running():
step_start = time.time()
mj.mj_step(model, data)
viewer.sync()
time_until_next_step = model.opt.timestep - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step) Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 2 comments 4 replies
-
There is Is that what you're looking for? |
Beta Was this translation helpful? Give feedback.
-
And of course if you know the name there is always mjs_findElement: I think you can also use a string here like |
Beta Was this translation helpful? Give feedback.
And of course if you know the name there is always mjs_findElement:
mjs_findElement(spec, mujoco.mjtObj.mjOBJ_GEOM, 'my_geom')
I think you can also use a string here like
mjs_findElement(spec, 'geom', 'my_geom')
, but I'm not sure if we implemented that 🙂