Skip to content

Help Needed Capturing Frames from Custom Base Camera Using MuJoCo Python API #29

@Srivastava-Burugu

Description

@Srivastava-Burugu

Hello,

First of all, I truly appreciate the work behind this project and how accessible it's been made to the community — thank you for that.

I’m currently exploring Sim2Sim validation with a modified robot model, and I’ve added a new camera to the base of the robot in the MJCF file. I’m using the Python bindings of MuJoCo to run the simulation and would like to capture images from this "base_camera".

I’m relatively new to MuJoCo, and while the simulator runs well using launch_passive(), I’m struggling to grab frames from the added camera in a stable and repeatable way.

Here’s what I’ve attempted:

  • I’m launching the simulation using mujoco.viewer.launch_passive() which works well visually.
  • Unfortunately, the passive viewer doesn't expose its internal MjrContext, making it difficult to use mjr_render() and mjr_readPixels() for frame capture.
  • If I try to create a new MjrContext in the same thread, the simulation abruptly crashes without an error — presumably due to OpenGL context conflicts.
  • I then tried spawning a dedicated thread to create a fresh context and capture frames offscreen. This resolves the viewer crash,but eventually throws a framebuffer-related error (e.g., "frame buffer is not complete, error 0x0"), preventing successful rendering.

Change that I have made to the mujoco.py script for MujocoEnv Class

import threading
import queue
import numpy as np
import mujoco
import mujoco.viewer

class MujocoEnv:
    def __init__(self, cfg):
        self.cfg = cfg

        if cfg.num_joints == 22:
            xml_path = "source/berkeley_humanoid_lite_assets/data/mjcf/bhl_scene.xml"
        else:
            xml_path = "source/berkeley_humanoid_lite_assets/data/mjcf/bhl_biped_scene.xml"

        self.mj_model = mujoco.MjModel.from_xml_path(xml_path)
        self.mj_data = mujoco.MjData(self.mj_model)
        self.mj_model.opt.timestep = self.cfg.physics_dt

        # Launch passive viewer
        self.mj_viewer = mujoco.viewer.launch_passive(self.mj_model, self.mj_data)

        # Start threaded frame capture
        self.frame_queue = queue.Queue(maxsize=1)
        self._start_frame_capture_thread()

    def _start_frame_capture_thread(self, width=640, height=480):
        """Background thread that captures frames from 'base_camera' using its own context."""
        def capture_loop():
            try:
                cam = mujoco.MjvCamera()
                cam.type = mujoco.mjtCamera.mjCAMERA_FIXED
                cam.fixedcamid = self.mj_model.camera("base_camera").id

                scene = mujoco.MjvScene(self.mj_model, maxgeom=1000)
                opt = mujoco.MjvOption()
                context = mujoco.MjrContext(self.mj_model, mujoco.mjtFontScale.mjFONTSCALE_100)
                viewport = mujoco.MjrRect(0, 0, width, height)

                while self.mj_viewer.is_running():
                    mujoco.mjv_updateScene(self.mj_model, self.mj_data, opt, None, cam,
                                           mujoco.mjtCatBit.mjCAT_ALL, scene)

                    rgb = np.zeros((height, width, 3), dtype=np.uint8)
                    depth = np.zeros((height, width), dtype=np.float32)

                    mujoco.mjr_render(viewport, scene, context)
                    mujoco.mjr_readPixels(rgb, depth, viewport, context)

                    # Update queue with latest frame
                    if not self.frame_queue.empty():
                        try:
                            self.frame_queue.get_nowait()
                        except queue.Empty:
                            pass
                    self.frame_queue.put(rgb)

                    time.sleep(self.cfg.physics_dt)

            except Exception as e:
                print(f"[FrameCapture] Error: {e}")
            finally:
                mujoco.mjr_freeContext(context)
                mujoco.mjv_freeScene(scene)

        threading.Thread(target=capture_loop, daemon=True).start()

    def get_latest_camera_image(self) -> np.ndarray | None:
        """Retrieve the most recent RGB frame from base_camera."""
        if not self.frame_queue.empty():
            return self.frame_queue.get()
        return None

At this point, I’m unsure what the correct or recommended approach is for capturing frames from a custom camera while running the simulation interactively via the passive viewer.

System Info:

  • OS: Windows 10
  • MuJoCo version: 3.3.4
  • Python bindings: Using mujoco official module
  • Viewer: Passive mode (launch_passive)
  • Robot: Custom MJCF with "base_camera" added

Could someone help me with capturing camera frames in an interactive viewer setup,or knows how to access the rendering context safely (or bypass it entirely for offscreen rendering), I’d greatly appreciate guidance or suggestions.

Thanks again!

Metadata

Metadata

Assignees

No one assigned

    Labels

    questionFurther information is requested

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions