def render_offscreen(self, width: int, height: int, mode: RenderMode = RenderMode.RGB, camera_id: int = -1) -> np.ndarray: """Renders the camera view as a NumPy array of pixels. Args: width: The viewport width (pixels). height: The viewport height (pixels). mode: The rendering mode. camera_id: The ID of the camera to render from. By default, uses the free camera. Returns: A NumPy array of the pixels. """ mujoco = module.get_dm_mujoco() # TODO(michaelahn): Consider caching the camera. camera = mujoco.Camera(physics=self._physics, height=height, width=width, camera_id=camera_id) # Update the camera configuration for the free-camera. if camera_id == -1: self._update_camera( camera._render_camera, # pylint: disable=protected-access ) image = camera.render(depth=(mode == RenderMode.DEPTH), segmentation=(mode == RenderMode.SEGMENTATION)) camera._scene.free() # pylint: disable=protected-access return image
def _create_solver_sim(self): from adept_envs.simulation import module # only support self._use_dm_backend == True dm_mujoco = module.get_dm_mujoco() model_file = self.MODEL_TELEOP_SOLVER if model_file.endswith('.mjb'): self.solver_sim = dm_mujoco.Physics.from_binary_path(model_file) else: self.solver_sim = dm_mujoco.Physics.from_xml_path(model_file) from adept_envs.simulation.sim_robot import _patch_mjlib_accessors _patch_mjlib_accessors(self.solver_sim.model, self.solver_sim.data, True)
def __init__(self, physics, **kwargs): assert isinstance(physics, module.get_dm_mujoco().Physics), \ 'DMRenderer takes a DM Control Physics object.' super().__init__(**kwargs) self._physics = physics self._window = None # Set the camera to lookat the center of the geoms. (mujoco_py does # this automatically. if 'lookat' not in self._camera_settings: self._camera_settings['lookat'] = [ np.median(self._physics.data.geom_xpos[:, i]) for i in range(3) ]
def __init__(self, model_file: str, use_dm_backend: bool = False, camera_settings: Optional[Dict] = None): """Initializes a new simulation. Args: model_file: The MuJoCo XML model file to load. use_dm_backend: If True, uses DM Control's Physics (MuJoCo v2.0) as the backend for the simulation. Otherwise, uses mujoco_py (MuJoCo v1.5) as the backend. camera_settings: Settings to initialize the renderer's camera. This can contain the keys `distance`, `azimuth`, and `elevation`. """ self._use_dm_backend = use_dm_backend if not os.path.isfile(model_file): raise ValueError( '[MujocoSimRobot] Invalid model file path: {}'.format( model_file)) if self._use_dm_backend: dm_mujoco = module.get_dm_mujoco() if model_file.endswith('.mjb'): self.sim = dm_mujoco.Physics.from_binary_path(model_file) else: self.sim = dm_mujoco.Physics.from_xml_path(model_file) self.model = self.sim.model _patch_mjlib_accessors(self.model, self.sim.data, self._use_dm_backend) self.renderer = DMRenderer( self.sim, camera_settings=camera_settings) else: # Use mujoco_py mujoco_py = module.get_mujoco_py() self.model = mujoco_py.load_model_from_path(model_file) self.sim = mujoco_py.MjSim(self.model) self.renderer = MjPyRenderer( self.sim, camera_settings=camera_settings) self.data = self.sim.data
def get_mjlib(use_dm_backend): """Returns an object that exposes the low-level MuJoCo API.""" if use_dm_backend: return module.get_dm_mujoco().wrapper.mjbindings.mjlib else: return module.get_mujoco_py_mjlib()