mujoco icon indicating copy to clipboard operation
mujoco copied to clipboard

Example using Python bindings to visualize Mujoco scene

Open studywolf opened this issue 3 years ago • 7 comments
trafficstars

Hi,

I'm a researcher and I'm trying to use MuJoCo for training a neuromorphic controller.

I'm looking for some help with visualizing a simulation using the new Mujoco Python bindings.

I previously used mujoco-py to do the interfacing with Mujoco, but I'm interested to update to the latest Mujoco version. There is the render_test.py example in the repo, but that doesn't actually show the full use case of visualizing a scene. I've scoured the documentation but not found a full description there either. I don't have a lot of familiarity with GLFW, so I'm hoping that someone can just whip up a quick python script that shows visualization of one of the default models. I'll keep working on it, but this would really help me out! (and I think be a useful example to have explicitly in the documentation) Thanks!

studywolf avatar Jul 20 '22 17:07 studywolf

Take a look at our colabs (linked in the README). They use dm_control for rendering from Python.

We also intend to add some example Python code with no dependency on dm_control, but they would be a subset of what is already in dm_control.

yuvaltassa avatar Jul 20 '22 17:07 yuvaltassa

Ah, okeydoke. Is there a time line on that? My goal was to remove dependencies! :D Looking through the Colab and then the dm_control documentation it seems like the rendering is buried pretty deeply in there, and not something I'll be able to pull out quickly.

studywolf avatar Jul 20 '22 17:07 studywolf

Actually we already have a colab that just needs cleaning up and maybe some of the rendering stuff pulled into library functions. I'll try and see if we we can either finish that soon or if not maybe we can find a quick way to share it with you. I hope to update here in the next few days.

yuvaltassa avatar Jul 20 '22 17:07 yuvaltassa

Oh, that would be excellent, thanks!

studywolf avatar Jul 20 '22 17:07 studywolf

I took another look at the simulate.cc and decided to just work to try rendering from Python with that code as a reference (instead of the render_test.py) and was successful. There's no interaction, but a basic example running in Python! Posting here in case it's useful to anyone while the formal examples are built out. I used the 2link arm from the examples as a demo and just set the control signal for the first joint so I had a demo with movement.

This will let me keep going for now, but looking forward to a set up with a UI!

import mujoco
import numpy as np

model = mujoco.MjModel.from_xml_string(
"""<mujoco model="2-link 6-muscle arm">
  <option timestep="0.005" iterations="50" solver="Newton" tolerance="1e-10"/>

  <size njmax="50" nconmax="10" nstack="200"/>

  <visual>
    <rgba haze=".3 .3 .3 1"/>
  </visual>

  <default>
    <joint type="hinge" pos="0 0 0" axis="0 0 1" limited="true" range="0 120" damping="0.1"/>
    <muscle ctrllimited="true" ctrlrange="0 1"/>
  </default>

  <asset>
    <texture type="skybox" builtin="gradient" rgb1="0.6 0.6 0.6" rgb2="0 0 0" width="512" height="512"/>
    <texture name="texplane" type="2d" builtin="checker" rgb1=".25 .25 .25" rgb2=".3 .3 .3" width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
    <material name="matplane" reflectance="0.3" texture="texplane" texrepeat="1 1" texuniform="true"/>
  </asset>

  <worldbody>
    <geom name="floor" pos="0 0 -0.5" size="0 0 1" type="plane" material="matplane"/>

    <light directional="true" diffuse=".8 .8 .8" specular=".2 .2 .2" pos="0 0 5" dir="0 0 -1"/>

    <site name="s0" pos="-0.15 0 0" size="0.02"/>
    <site name="x0" pos="0 -0.15 0" size="0.02" rgba="0 .7 0 1" group="1"/>

    <body pos="0 0 0">
      <geom name="upper arm" type="capsule" size="0.045" fromto="0 0 0  0.5 0 0" rgba=".5 .1 .1 1"/>
      <joint name="shoulder"/>
      <geom name="shoulder" type="cylinder" pos="0 0 0" size=".1 .05" rgba=".5 .1 .8 .5" mass="0" group="1"/>

      <site name="s1" pos="0.15 0.06 0" size="0.02"/>
      <site name="s2" pos="0.15 -0.06 0" size="0.02"/>
      <site name="s3" pos="0.4 0.06 0" size="0.02"/>
      <site name="s4" pos="0.4 -0.06 0" size="0.02"/>
      <site name="s5" pos="0.25 0.1 0" size="0.02"/>
      <site name="s6" pos="0.25 -0.1 0" size="0.02"/>
      <site name="x1" pos="0.5 -0.15 0" size="0.02" rgba="0 .7 0 1" group="1"/>

      <body pos="0.5 0 0">
        <geom name="forearm" type="capsule" size="0.035" fromto="0 0 0  0.5 0 0" rgba=".5 .1 .1 1"/>
        <joint name="elbow"/>
        <geom name="elbow" type="cylinder" pos="0 0 0" size=".08 .05" rgba=".5 .1 .8 .5" mass="0" group="1"/>

        <site name="s7" pos="0.11 0.05 0" size="0.02"/>
        <site name="s8" pos="0.11 -0.05 0" size="0.02"/>
      </body>
    </body>
  </worldbody>

  <tendon>
    <spatial name="SF" width="0.01">
      <site site="s0"/>
      <geom geom="shoulder"/>
      <site site="s1"/>
    </spatial>

    <spatial name="SE" width="0.01">
      <site site="s0"/>
      <geom geom="shoulder" sidesite="x0"/>
      <site site="s2"/>
    </spatial>

    <spatial name="EF" width="0.01">
      <site site="s3"/>
      <geom geom="elbow"/>
      <site site="s7"/>
    </spatial>

    <spatial name="EE" width="0.01">
      <site site="s4"/>
      <geom geom="elbow" sidesite="x1"/>
      <site site="s8"/>
    </spatial>

    <spatial name="BF" width="0.009" rgba=".4 .6 .4 1">
      <site site="s0"/>
      <geom geom="shoulder"/>
      <site site="s5"/>
      <geom geom="elbow"/>
      <site site="s7"/>
    </spatial>

    <spatial name="BE" width="0.009" rgba=".4 .6 .4 1">
      <site site="s0"/>
      <geom geom="shoulder" sidesite="x0"/>
      <site site="s6"/>
      <geom geom="elbow" sidesite="x1"/>
      <site site="s8"/>
    </spatial>
  </tendon>

  <actuator>
    <muscle name="SF" tendon="SF"/>
    <muscle name="SE" tendon="SE"/>
    <muscle name="EF" tendon="EF"/>
    <muscle name="EE" tendon="EE"/>
    <muscle name="BF" tendon="BF"/>
    <muscle name="BE" tendon="BE"/>
  </actuator>
</mujoco>"""
)
data = mujoco.MjData(model)

glfw.init()
window = glfw.create_window(640, 480, "Hello World", None, None)
glfw.make_context_current(window)
glfw.swap_interval(1)


camera = mujoco.MjvCamera()
option = mujoco.MjvOption()
context = mujoco.MjrContext(model, mujoco.mjtFontScale.mjFONTSCALE_150)
scene = mujoco.MjvScene(model, maxgeom=100000)
perturb = mujoco.MjvPerturb()

mujoco.mjv_defaultCamera(camera)
mujoco.mjv_defaultPerturb(perturb)
mujoco.mjv_defaultOption(option)

# mujoco.mjr_defaultContext(context)
# mujoco.mjv_makeScene(model, scene, 1000)

simstart = 0.0
dt = 0.001
while not glfw.window_should_close(window):

    for ii in range(1):
        mujoco.mj_step(model, data)

    print(f"{data.qpos=}")
    data.ctrl[0] = -1
    viewport = mujoco.MjrRect(0, 0, 0, 0)
    viewport.width, viewport.height = glfw.get_framebuffer_size(window)

    mujoco.mjv_updateScene(
        model,
        data,
        option,
        perturb,
        camera,
        mujoco.mjtCatBit.mjCAT_ALL,
        scene)
    mujoco.mjr_render(viewport, scene, context)

    glfw.swap_buffers(window)
    glfw.poll_events()

glfw.terminate()

studywolf avatar Jul 20 '22 19:07 studywolf

Hi @studywolf perhaps this renderer I developed could be of use to you :)

rohanpsingh avatar Jul 22 '22 09:07 rohanpsingh

Ah, great, thanks! This is much better than building out my own while waiting for the updates!

studywolf avatar Jul 22 '22 13:07 studywolf

@yuvaltassa any updates?

studywolf avatar Sep 15 '22 12:09 studywolf

Hi @studywolf,

Thanks for the reminder. Yes, you can see a draft proposal of a new Renderer class in the LQR colab notebook we just released. @rohanpsingh, FYI.

I hope to finish converting the old dm_control-based tutorial notebook to native bindings soon as well.

If you wish to contribute, you might consider submitting this yourself :slightly_smiling_face:

yuvaltassa avatar Sep 20 '22 14:09 yuvaltassa

@yuvaltassa I think link to the colab notebook is broken: https://github.com/deepmind/mujoco/compare/main...rohanpsingh:mujoco:patch-2

rohanpsingh avatar Sep 20 '22 15:09 rohanpsingh