| import time |
| from collections import deque |
|
|
| import mujoco |
| import numpy as np |
| from PySide6.QtCore import Qt, QTimer, Signal |
| from PySide6.QtGui import QSurfaceFormat |
| from PySide6.QtOpenGL import QOpenGLWindow |
|
|
| format = QSurfaceFormat() |
| format.setDepthBufferSize(24) |
| format.setStencilBufferSize(8) |
| format.setSamples(4) |
| format.setSwapInterval(1) |
| format.setSwapBehavior(QSurfaceFormat.SwapBehavior.DoubleBuffer) |
| format.setVersion(2,0) |
| format.setRenderableType(QSurfaceFormat.RenderableType.OpenGL) |
| format.setProfile(QSurfaceFormat.CompatibilityProfile) |
| QSurfaceFormat.setDefaultFormat(format) |
|
|
|
|
| class Viewport(QOpenGLWindow): |
|
|
| updateRuntime = Signal(float) |
|
|
| def __init__(self, model, data, cam, opt, scn) -> None: |
| super().__init__() |
|
|
| self.model = model |
| self.data = data |
| self.cam = cam |
| self.opt = opt |
| self.scn = scn |
|
|
| self.camera_id = 0 |
|
|
| self.width = 0 |
| self.height = 0 |
| self.scale = 1.0 |
| self.__last_pos = None |
|
|
| self.runtime = deque(maxlen=1000) |
| self.timer = QTimer() |
| self.timer.setInterval(1/60*1000) |
| self.timer.timeout.connect(self.update) |
| self.timer.start() |
|
|
| def set_camera(self, camera_id: int): |
| """Set the active camera. 0 = free camera, >0 = fixed camera (index-1).""" |
| self.camera_id = camera_id |
| self.update() |
|
|
| def _apply_selected_camera(self): |
| """Apply the selected camera: 0 = free, >0 = fixed.""" |
| if self.camera_id == 0: |
| self.cam.type = mujoco.mjtCamera.mjCAMERA_FREE |
| self.cam.fixedcamid = -1 |
| elif self.model.ncam > 0 and 1 <= self.camera_id <= self.model.ncam: |
| self.cam.type = mujoco.mjtCamera.mjCAMERA_FIXED |
| self.cam.fixedcamid = self.camera_id - 1 |
|
|
| def mousePressEvent(self, event): |
| self.__last_pos = event.position() |
|
|
| def mouseMoveEvent(self, event): |
| if event.buttons() & Qt.MouseButton.RightButton: |
| action = mujoco.mjtMouse.mjMOUSE_MOVE_V |
| elif event.buttons() & Qt.MouseButton.LeftButton: |
| action = mujoco.mjtMouse.mjMOUSE_ROTATE_V |
| elif event.buttons() & Qt.MouseButton.MiddleButton: |
| action = mujoco.mjtMouse.mjMOUSE_ZOOM |
| else: |
| return |
| pos = event.position() |
| dx = pos.x() - self.__last_pos.x() |
| dy = pos.y() - self.__last_pos.y() |
| mujoco.mjv_moveCamera(self.model, action, dx / self.height, dy / self.height, self.scn, self.cam) |
| self.__last_pos = pos |
|
|
| def wheelEvent(self, event): |
| mujoco.mjv_moveCamera(self.model, mujoco.mjtMouse.mjMOUSE_ZOOM, 0, -0.0005 * event.angleDelta().y(), self.scn, self.cam) |
|
|
| def initializeGL(self): |
| self.con = mujoco.MjrContext(self.model, mujoco.mjtFontScale.mjFONTSCALE_100) |
|
|
| def resizeGL(self, w, h): |
| self.width = w |
| self.height = h |
|
|
| def setScreenScale(self, scaleFactor: float) -> None: |
| """ Sets a scale factor that is used to scale the OpenGL window to accommodate |
| the high DPI scaling Qt does. |
| """ |
| self.scale = scaleFactor |
|
|
| def paintGL(self) -> None: |
| t = time.time() |
| self._apply_selected_camera() |
| mujoco.mjv_updateScene(self.model, self.data, self.opt, None, self.cam, mujoco.mjtCatBit.mjCAT_ALL, self.scn) |
| viewport = mujoco.MjrRect(0, 0, int(self.width * self.scale), int(self.height * self.scale)) |
| mujoco.mjr_render(viewport, self.scn, self.con) |
|
|
| self.runtime.append(time.time()-t) |
| self.updateRuntime.emit(np.average(self.runtime)) |
|
|