|
86 | 86 |
|
87 | 87 | // Set up the condition variable to pass control back to the macOS main thread.
|
88 | 88 | gil = cpython.PyGILState_Ensure();
|
89 |
| - cpython.PyRun_SimpleStringFlags("import threading; cond = threading.Condition()", nullptr); |
| 89 | + cpython.PyRun_SimpleStringFlags(R"( |
| 90 | +def _mjpython_make_cond(): |
| 91 | + # Don't pollute the global namespace. |
| 92 | + global _mjpython_make_cond |
| 93 | + del _mjpython_make_cond |
| 94 | +
|
| 95 | + import threading |
| 96 | +
|
| 97 | + global cond |
| 98 | + cond = threading.Condition() |
| 99 | +
|
| 100 | +_mjpython_make_cond() |
| 101 | +)", nullptr); |
90 | 102 | py_initialized.store(true);
|
91 | 103 |
|
92 | 104 | // Wait until GLFW is initialized on macOS main thread, set up the queue and an atexit hook
|
93 | 105 | // to enqueue a termination flag upon exit.
|
94 | 106 | cpython.PyRun_SimpleStringFlags(R"(
|
95 |
| -import atexit |
96 |
| -
|
97 |
| -# The mujoco.viewer module should only be imported here after glfw.init() in the macOS main thread. |
98 |
| -with cond: |
99 |
| - cond.wait() |
100 |
| -import mujoco.viewer |
101 |
| -
|
102 |
| -# Similar to a queue.Queue(maxsize=1), but where only one active task is allowed at a time. |
103 |
| -# With queue.Queue(1), another item is allowed to be enqueued before task_done is called. |
104 |
| -class _MjPythonImpl(mujoco.viewer._MjPythonBase): |
105 |
| -
|
106 |
| - # Termination statuses |
107 |
| - NOT_TERMINATED = 0 |
108 |
| - TERMINATION_REQUESTED = 1 |
109 |
| - TERMINATION_ACCEPTED = 2 |
110 |
| - TERMINATED = 3 |
111 |
| -
|
112 |
| - def __init__(self): |
113 |
| - self._cond = threading.Condition() |
114 |
| - self._task = None |
115 |
| - self._termination = self.__class__.NOT_TERMINATED |
116 |
| - self._busy = False |
117 |
| -
|
118 |
| - def launch_on_ui_thread( |
119 |
| - self, |
120 |
| - model, |
121 |
| - data, |
122 |
| - handle_return, |
123 |
| - key_callback, |
124 |
| - show_left_ui, |
125 |
| - show_right_ui, |
126 |
| - ): |
127 |
| - with self._cond: |
128 |
| - if self._busy or self._task is not None: |
129 |
| - raise RuntimeError('another MuJoCo viewer is already open') |
130 |
| - else: |
131 |
| - self._task = ( |
132 |
| - model, |
133 |
| - data, |
134 |
| - handle_return, |
135 |
| - key_callback, |
136 |
| - show_left_ui, |
137 |
| - show_right_ui, |
138 |
| - ) |
139 |
| - self._cond.notify() |
140 |
| -
|
141 |
| - def terminate(self): |
142 |
| - with self._cond: |
143 |
| - self._termination = self.__class__.TERMINATION_REQUESTED |
144 |
| - self._cond.notify() |
145 |
| - self._cond.wait_for( |
146 |
| - lambda: self._termination == self.__class__.TERMINATED) |
147 |
| -
|
148 |
| - def get(self): |
149 |
| - with self._cond: |
150 |
| - self._cond.wait_for( |
151 |
| - lambda: self._task is not None or self._termination) |
152 |
| -
|
153 |
| - if self._termination: |
154 |
| - if self._termination == self.__class__.TERMINATION_REQUESTED: |
155 |
| - self._termination = self.__class__.TERMINATION_ACCEPTED |
156 |
| - return None |
157 |
| -
|
158 |
| - task = self._task |
159 |
| - self._busy = True |
| 107 | +def _mjpython_init(): |
| 108 | + # Don't pollute the global namespace. |
| 109 | + global _mjpython_init |
| 110 | + del _mjpython_init |
| 111 | +
|
| 112 | + import atexit |
| 113 | + import threading |
| 114 | +
|
| 115 | + # The mujoco.viewer module should only be imported after glfw.init() in the macOS main thread. |
| 116 | + with cond: |
| 117 | + cond.wait() |
| 118 | + import mujoco.viewer |
| 119 | +
|
| 120 | + # Similar to a queue.Queue(maxsize=1), but where only one active task is allowed at a time. |
| 121 | + # With queue.Queue(1), another item is allowed to be enqueued before task_done is called. |
| 122 | + class _MjPythonImpl(mujoco.viewer._MjPythonBase): |
| 123 | +
|
| 124 | + # Termination statuses |
| 125 | + NOT_TERMINATED = 0 |
| 126 | + TERMINATION_REQUESTED = 1 |
| 127 | + TERMINATION_ACCEPTED = 2 |
| 128 | + TERMINATED = 3 |
| 129 | +
|
| 130 | + def __init__(self): |
| 131 | + self._cond = threading.Condition() |
160 | 132 | self._task = None
|
161 |
| - return task |
162 |
| -
|
163 |
| - def done(self): |
164 |
| - with self._cond: |
| 133 | + self._termination = self.__class__.NOT_TERMINATED |
165 | 134 | self._busy = False
|
166 |
| - if self._termination == self.__class__.TERMINATION_ACCEPTED: |
167 |
| - self._termination = self.__class__.TERMINATED |
168 |
| - self._cond.notify() |
169 | 135 |
|
| 136 | + def launch_on_ui_thread( |
| 137 | + self, |
| 138 | + model, |
| 139 | + data, |
| 140 | + handle_return, |
| 141 | + key_callback, |
| 142 | + show_left_ui, |
| 143 | + show_right_ui, |
| 144 | + ): |
| 145 | + with self._cond: |
| 146 | + if self._busy or self._task is not None: |
| 147 | + raise RuntimeError('another MuJoCo viewer is already open') |
| 148 | + else: |
| 149 | + self._task = ( |
| 150 | + model, |
| 151 | + data, |
| 152 | + handle_return, |
| 153 | + key_callback, |
| 154 | + show_left_ui, |
| 155 | + show_right_ui, |
| 156 | + ) |
| 157 | + self._cond.notify() |
| 158 | +
|
| 159 | + def terminate(self): |
| 160 | + with self._cond: |
| 161 | + self._termination = self.__class__.TERMINATION_REQUESTED |
| 162 | + self._cond.notify() |
| 163 | + self._cond.wait_for( |
| 164 | + lambda: self._termination == self.__class__.TERMINATED) |
| 165 | +
|
| 166 | + def get(self): |
| 167 | + with self._cond: |
| 168 | + self._cond.wait_for( |
| 169 | + lambda: self._task is not None or self._termination) |
| 170 | +
|
| 171 | + if self._termination: |
| 172 | + if self._termination == self.__class__.TERMINATION_REQUESTED: |
| 173 | + self._termination = self.__class__.TERMINATION_ACCEPTED |
| 174 | + return None |
| 175 | +
|
| 176 | + task = self._task |
| 177 | + self._busy = True |
| 178 | + self._task = None |
| 179 | + return task |
| 180 | +
|
| 181 | + def done(self): |
| 182 | + with self._cond: |
| 183 | + self._busy = False |
| 184 | + if self._termination == self.__class__.TERMINATION_ACCEPTED: |
| 185 | + self._termination = self.__class__.TERMINATED |
| 186 | + self._cond.notify() |
170 | 187 |
|
171 |
| -mujoco.viewer._MJPYTHON = _MjPythonImpl() |
172 |
| -atexit.register(mujoco.viewer._MJPYTHON.terminate) |
173 |
| -del _MjPythonImpl # Don't pollute globals for user script. |
174 | 188 |
|
175 |
| -with cond: |
176 |
| - cond.notify() |
177 |
| -del cond # Don't pollute globals for user script. |
| 189 | + mujoco.viewer._MJPYTHON = _MjPythonImpl() |
| 190 | + atexit.register(mujoco.viewer._MJPYTHON.terminate) |
| 191 | +
|
| 192 | + with cond: |
| 193 | + cond.notify() |
| 194 | +
|
| 195 | +_mjpython_init() |
178 | 196 | )", nullptr);
|
179 | 197 |
|
180 | 198 | // Run the Python interpreter main loop.
|
@@ -283,47 +301,56 @@ int main(int argc, char** argv) {
|
283 | 301 | // to finish setting up _MJPYTHON, then serve incoming viewer launch requests.
|
284 | 302 | PyGILState_STATE gil = cpython.PyGILState_Ensure();
|
285 | 303 | cpython.PyRun_SimpleStringFlags(R"(
|
286 |
| -import ctypes |
287 |
| -
|
288 |
| -# GLFW must be initialized on the OS main thread (i.e. here). |
289 |
| -import glfw |
290 |
| -import mujoco.viewer |
291 |
| -
|
292 |
| -glfw.init() |
293 |
| -glfw.poll_events() |
294 |
| -ctypes.CDLL(None).mjpython_hide_dock_icon() |
295 |
| -
|
296 |
| -# Wait for Python main thread to finish setting up _MJPYTHON |
297 |
| -with cond: |
298 |
| - cond.notify() |
299 |
| - cond.wait() |
300 |
| -
|
301 |
| -while True: |
302 |
| - try: |
303 |
| - # Wait for an incoming payload. |
304 |
| - task = mujoco.viewer._MJPYTHON.get() |
305 |
| -
|
306 |
| - # None means that we are exiting. |
307 |
| - if task is None: |
308 |
| - glfw.terminate() |
309 |
| - break |
310 |
| -
|
311 |
| - # Otherwise, launch the viewer. |
312 |
| - model, data, handle_return, key_callback, show_left_ui, show_right_ui = task |
313 |
| - ctypes.CDLL(None).mjpython_show_dock_icon() |
314 |
| - mujoco.viewer._launch_internal( |
315 |
| - model, |
316 |
| - data, |
317 |
| - run_physics_thread=False, |
318 |
| - handle_return=handle_return, |
319 |
| - key_callback=key_callback, |
320 |
| - show_left_ui=show_left_ui, |
321 |
| - show_right_ui=show_right_ui, |
322 |
| - ) |
323 |
| - ctypes.CDLL(None).mjpython_hide_dock_icon() |
324 |
| -
|
325 |
| - finally: |
326 |
| - mujoco.viewer._MJPYTHON.done() |
| 304 | +def _mjpython_main(): |
| 305 | + # Don't pollute the global namespace. |
| 306 | + global _mjpython_main |
| 307 | + del _mjpython_main |
| 308 | +
|
| 309 | + import ctypes |
| 310 | +
|
| 311 | + # GLFW must be initialized on the OS main thread (i.e. here). |
| 312 | + import glfw |
| 313 | + import mujoco.viewer |
| 314 | +
|
| 315 | + glfw.init() |
| 316 | + glfw.poll_events() |
| 317 | + ctypes.CDLL(None).mjpython_hide_dock_icon() |
| 318 | +
|
| 319 | + # Wait for Python main thread to finish setting up _MJPYTHON |
| 320 | + global cond |
| 321 | + with cond: |
| 322 | + cond.notify() |
| 323 | + cond.wait() |
| 324 | + del cond |
| 325 | +
|
| 326 | + while True: |
| 327 | + try: |
| 328 | + # Wait for an incoming payload. |
| 329 | + task = mujoco.viewer._MJPYTHON.get() |
| 330 | +
|
| 331 | + # None means that we are exiting. |
| 332 | + if task is None: |
| 333 | + glfw.terminate() |
| 334 | + break |
| 335 | +
|
| 336 | + # Otherwise, launch the viewer. |
| 337 | + model, data, handle_return, key_callback, show_left_ui, show_right_ui = task |
| 338 | + ctypes.CDLL(None).mjpython_show_dock_icon() |
| 339 | + mujoco.viewer._launch_internal( |
| 340 | + model, |
| 341 | + data, |
| 342 | + run_physics_thread=False, |
| 343 | + handle_return=handle_return, |
| 344 | + key_callback=key_callback, |
| 345 | + show_left_ui=show_left_ui, |
| 346 | + show_right_ui=show_right_ui, |
| 347 | + ) |
| 348 | + ctypes.CDLL(None).mjpython_hide_dock_icon() |
| 349 | +
|
| 350 | + finally: |
| 351 | + mujoco.viewer._MJPYTHON.done() |
| 352 | +
|
| 353 | +_mjpython_main() |
327 | 354 | )", nullptr);
|
328 | 355 | cpython.PyGILState_Release(gil);
|
329 | 356 |
|
|
0 commit comments