google-deepmind / mujoco

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

Issue with Camera Visibility of Dynamically Merged XML Models in MuJoCo #1679

Closed kankannali closed 5 months ago

kankannali commented 5 months ago

Dear MuJoCo Support Team,

I am currently encountering a problem with model visualization in a reinforcement learning setup using MuJoCo. To facilitate training in randomized environments, I dynamically generate voxel environments in XML format using ET.SubElement and merge these with a primary robot model (robot.xml). Here’s a brief overview of my process: I initialize my simulation with self.model = mujoco.MjModel.from_xml_path("robot.xml").

Before experiments, I use a custom function merge_xmls to merge robot.xml with the dynamically generated environment model (env.xml) in Def reset. The function parses both XML files, appends elements from env.xml to robot.xml, and saves the combined result in merged.xml.

def merge_xmls(self, main_xml, *additional_xmls):
        main_tree = ET.parse(main_xml)
        main_root = main_tree.getroot()
        body_names = []
        main_tendon = main_root.find("tendon")
        if main_tendon is None:
            main_tendon = ET.SubElement(main_root, "tendon")
        for add_xml in additional_xmls:
            add_tree = ET.parse(add_xml)
            add_root = add_tree.getroot()
            for elem in add_root.find("worldbody"):
                main_root.find("worldbody").append(elem)
                body_names.append(elem.get('name')) 
            add_tendon = add_root.find("tendon")
            if add_tendon is not None:
                for spatial in add_tendon:
                    main_tendon.append(spatial)
        merged_path = "merged.xml"
        with open(merged_path, "wb") as f:
            f.write(ET.tostring(main_root))
        return merged_path, body_names  

I then reload the model from merged.xml using mujoco.MjModel.from_xml_path.

def reset(self, seed=None, return_info=False, options=None):
      self.env_xml = generate_box_xml('Reinforcement/train') 
      merged_xml, body_names = self.merge_xmls(self.robot_xml, self.env_xml)
      self.model = mujoco.MjModel.from_xml_path(merged_xml)
      self.data = mujoco.MjData(self.model)
      mujoco.mj_forward(self.model, self.data)
      self.reset_robot_state()
      if self.viewer is not None:
      self.viewer._sim().load(self.model, self.data, "")
......

Despite the successful merging and rendering in the simulation window (where objects from env.xml are visible), there is a significant issue: objects from env.xml are not visible in the RGB images rendered from the camera defined in robot.xml. The camera is set up as follows:

<mujoco>
  <visual>
    <global offwidth="1280" offheight="720" />
  </visual>
  <worldbody>
    ......
    <camera name="rgbd_camera" pos="0 0 0" euler="90 -90 0"/>
    ......
  </worldbody>
</mujoco>

My codes for saving RGB-D data from camera is following:

def get_rgbd_data(self):
    camera_name = 'rgbd_camera' 
    camera_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_CAMERA, camera_name)
    self.renderer.update_scene(self.data, camera=camera_id)
    rgb_image = self.renderer.render()
    rgb_image = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR)
    self.renderer.enable_depth_rendering()
    depth_image = self.renderer.render()
    self.renderer.disable_depth_rendering()
    self.save_rgbd_data(rgb_image, depth_image, self.step_count)

The following image shows the scene inside the render visualization window(Under the camera's perspective) and the RGB image saved by my code at the end image image

It seems the camera fails to capture the newly added objects from env.xml in its visual field. Could you please provide guidance on how to ensure that dynamically added objects are visible in camera renders? Are there specific steps or settings I should consider to resolve this issue?

Thank you for your assistance.

kankannali commented 5 months ago

I am currently facing challenges with my MuJoCo simulation setup, particularly concerning model visualization and camera rendering in a reinforcement learning context. My workflow involves dynamically generating voxel environments for randomization in training, which are merged with a base robot model using custom XML processing.

Initial Issue with Camera Visibility: I use a function to merge 'robot.xml' with dynamically generated 'env.xml' files. After merging and reloading the model from the combined 'merged.xml', the objects from 'env.xml' are visible in the MuJoCo simulation window but not in the RGB images rendered by the camera configured in 'robot.xml'. This camera issue persists despite the objects being clearly visible in direct rendering.

Attempted Solution and New Issue: Following a suggestion from this GitHub issue, I implemented dynamic loading of new XML files using self.viewer._sim().load(model, data, ""), which successfully updates the visual model in the MuJoCo visualization window. However, this update did not resolve the camera's inability to capture the newly added objects in its rendered images.

To initialize the camera rendering, I use:

self.renderer = mujoco.Renderer(self.model, height=720, width=1280)

Recently, attempting to refresh the rendering setup by reinitializing the renderer with the same dimensions after a reset and loading a completely new XML model resulted in corrupted RGB-D images, displaying only garbled data.