From 2cdef0987a3c3fb91de39ab30a6cde2a9d5e62ef Mon Sep 17 00:00:00 2001 From: Pascal Roth Date: Mon, 8 Sep 2025 14:40:03 +0200 Subject: [PATCH 1/3] fix mem leak in video recorder --- scripts/benchmarks/benchmark_non_rl.py | 3 +- scripts/benchmarks/benchmark_rlgames.py | 3 +- scripts/benchmarks/benchmark_rsl_rl.py | 3 +- .../reinforcement_learning/rl_games/play.py | 3 +- .../reinforcement_learning/rl_games/train.py | 3 +- scripts/reinforcement_learning/rsl_rl/play.py | 3 +- .../reinforcement_learning/rsl_rl/train.py | 3 +- scripts/reinforcement_learning/sb3/play.py | 3 +- scripts/reinforcement_learning/sb3/train.py | 3 +- scripts/reinforcement_learning/skrl/play.py | 3 +- scripts/reinforcement_learning/skrl/train.py | 3 +- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 9 +++++ source/isaaclab/isaaclab/utils/recorder.py | 40 +++++++++++++++++++ .../isaaclab_tasks/test/test_record_video.py | 4 +- 15 files changed, 75 insertions(+), 13 deletions(-) create mode 100644 source/isaaclab/isaaclab/utils/recorder.py diff --git a/scripts/benchmarks/benchmark_non_rl.py b/scripts/benchmarks/benchmark_non_rl.py index 295436e75f3..861fac7ee7b 100644 --- a/scripts/benchmarks/benchmark_non_rl.py +++ b/scripts/benchmarks/benchmark_non_rl.py @@ -84,6 +84,7 @@ from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict +from isaaclab.utils.recorder import RecordVideo import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils.hydra import hydra_task_config @@ -138,7 +139,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) task_startup_time_end = time.perf_counter_ns() diff --git a/scripts/benchmarks/benchmark_rlgames.py b/scripts/benchmarks/benchmark_rlgames.py index 2394228efc9..c0647d4963d 100644 --- a/scripts/benchmarks/benchmark_rlgames.py +++ b/scripts/benchmarks/benchmark_rlgames.py @@ -76,6 +76,7 @@ from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper @@ -190,7 +191,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rl-games env = RlGamesVecEnvWrapper(env, rl_device, clip_obs, clip_actions) diff --git a/scripts/benchmarks/benchmark_rsl_rl.py b/scripts/benchmarks/benchmark_rsl_rl.py index 56207f4fe82..26d3e49fd83 100644 --- a/scripts/benchmarks/benchmark_rsl_rl.py +++ b/scripts/benchmarks/benchmark_rsl_rl.py @@ -76,6 +76,7 @@ from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlVecEnvWrapper @@ -183,7 +184,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rsl-rl env = RslRlVecEnvWrapper(env) diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index dd2185b82b0..e9280afcc17 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -75,6 +75,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper @@ -154,7 +155,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rl-games env = RlGamesVecEnvWrapper(env, rl_device, clip_obs, clip_actions, obs_groups, concate_obs_groups) diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index cc1e54b1756..c5a008f7166 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -80,6 +80,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper @@ -177,7 +178,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rl-games env = RlGamesVecEnvWrapper(env, rl_device, clip_obs, clip_actions, obs_groups, concate_obs_groups) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 9e89c6ff318..be50e7fae47 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -70,6 +70,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rsl_rl import RslRlBaseRunnerCfg, RslRlVecEnvWrapper, export_policy_as_jit, export_policy_as_onnx @@ -129,7 +130,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rsl-rl env = RslRlVecEnvWrapper(env, clip_actions=agent_cfg.clip_actions) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 33bfc9f63d4..9c07f0e1f5f 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -89,6 +89,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.rsl_rl import RslRlBaseRunnerCfg, RslRlVecEnvWrapper @@ -171,7 +172,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for rsl-rl env = RslRlVecEnvWrapper(env, clip_actions=agent_cfg.clip_actions) diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 05c52390749..d27bb8b704a 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -79,6 +79,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.sb3 import Sb3VecEnvWrapper, process_sb3_cfg @@ -147,7 +148,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for stable baselines env = Sb3VecEnvWrapper(env, fast_variant=not args_cli.keep_all_info) diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index ba45398f108..30791721958 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -92,6 +92,7 @@ def cleanup_pbar(*args): ) from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.sb3 import Sb3VecEnvWrapper, process_sb3_cfg @@ -169,7 +170,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for stable baselines env = Sb3VecEnvWrapper(env, fast_variant=not args_cli.keep_all_info) diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index 990ef5b558d..fd24022c1fd 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -106,6 +106,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.skrl import SkrlVecEnvWrapper @@ -188,7 +189,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, expe } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for skrl env = SkrlVecEnvWrapper(env, ml_framework=args_cli.ml_framework) # same as: `wrap_env(env, wrapper="auto")` diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index e3399f204b5..201874c23a2 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -105,6 +105,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml +from isaaclab.utils.recorder import RecordVideo from isaaclab_rl.skrl import SkrlVecEnvWrapper @@ -199,7 +200,7 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen } print("[INFO] Recording videos during training.") print_dict(video_kwargs, nesting=4) - env = gym.wrappers.RecordVideo(env, **video_kwargs) + env = RecordVideo(env, **video_kwargs) # wrap around environment for skrl env = SkrlVecEnvWrapper(env, ml_framework=args_cli.ml_framework) # same as: `wrap_env(env, wrapper="auto")` diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 792634e1052..8b426e2d302 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.45.12" +version = "0.45.13" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 1578f89be9d..73a0d23e8aa 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.45.13 (2025-09-08) +~~~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed memory leak of gymnasium video recording wrapper in the :class:`~isaaclab.utils.recorder.RecordVideo` class. + + 0.45.12 (2025-09-05) ~~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/utils/recorder.py b/source/isaaclab/isaaclab/utils/recorder.py new file mode 100644 index 00000000000..e39ea016bd4 --- /dev/null +++ b/source/isaaclab/isaaclab/utils/recorder.py @@ -0,0 +1,40 @@ +from __future__ import annotations + +import gc +import os + +import gymnasium as gym +from gymnasium import error, logger + + +class RecordVideo(gym.wrappers.RecordVideo): + """Fix gym wrapper to avoid memory leaks.""" + + def stop_recording(self): + """Stop current recording and saves the video.""" + assert self.recording, "stop_recording was called, but no recording was started" + + if len(self.recorded_frames) == 0: + logger.warn("Ignored saving a video as there were zero frames to save.") + else: + try: + from moviepy.video.io.ImageSequenceClip import ImageSequenceClip + except ImportError as e: + raise error.DependencyNotInstalled( + 'MoviePy is not installed, run `pip install "gymnasium[other]"`' + ) from e + + clip = ImageSequenceClip(self.recorded_frames, fps=self.frames_per_sec) + moviepy_logger = None if self.disable_logger else "bar" + path = os.path.join(self.video_folder, f"{self._video_name}.mp4") + clip.write_videofile(path, logger=moviepy_logger) + + del clip + + del self.recorded_frames + self.recorded_frames = [] + self.recording = False + self._video_name = None + + if self.gc_trigger and self.gc_trigger(self.episode_id): + gc.collect() diff --git a/source/isaaclab_tasks/test/test_record_video.py b/source/isaaclab_tasks/test/test_record_video.py index 9258fd2119f..a6cdde144d4 100644 --- a/source/isaaclab_tasks/test/test_record_video.py +++ b/source/isaaclab_tasks/test/test_record_video.py @@ -21,6 +21,8 @@ import pytest from env_test_utils import setup_environment +from isaaclab.utils.recorder import RecordVideo + import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import parse_env_cfg @@ -53,7 +55,7 @@ def test_record_video(task_name, setup_video_params): # directory to save videos task_videos_dir = os.path.join(videos_dir, task_name) # wrap environment to record videos - env = gym.wrappers.RecordVideo( + env = RecordVideo( env, task_videos_dir, step_trigger=step_trigger, From f9e3846a2e28e0bf5bc39d7611435f8bd95ef7cc Mon Sep 17 00:00:00 2001 From: Pascal Roth Date: Mon, 8 Sep 2025 15:27:38 +0200 Subject: [PATCH 2/3] formatter --- source/isaaclab/isaaclab/utils/recorder.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/source/isaaclab/isaaclab/utils/recorder.py b/source/isaaclab/isaaclab/utils/recorder.py index e39ea016bd4..7b943240116 100644 --- a/source/isaaclab/isaaclab/utils/recorder.py +++ b/source/isaaclab/isaaclab/utils/recorder.py @@ -1,9 +1,13 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + from __future__ import annotations import gc -import os - import gymnasium as gym +import os from gymnasium import error, logger @@ -28,7 +32,7 @@ def stop_recording(self): moviepy_logger = None if self.disable_logger else "bar" path = os.path.join(self.video_folder, f"{self._video_name}.mp4") clip.write_videofile(path, logger=moviepy_logger) - + del clip del self.recorded_frames From 90faa244a9bd9fe2c41de9d2419ccdfbfc8eac45 Mon Sep 17 00:00:00 2001 From: Pascal Roth Date: Tue, 9 Sep 2025 09:14:54 +0200 Subject: [PATCH 3/3] change to monkey patch --- scripts/benchmarks/benchmark_non_rl.py | 6 ++- scripts/benchmarks/benchmark_rlgames.py | 7 ++- scripts/benchmarks/benchmark_rsl_rl.py | 7 ++- .../reinforcement_learning/rl_games/play.py | 6 ++- .../reinforcement_learning/rl_games/train.py | 6 ++- scripts/reinforcement_learning/rsl_rl/play.py | 6 ++- .../reinforcement_learning/rsl_rl/train.py | 6 ++- scripts/reinforcement_learning/sb3/play.py | 6 ++- scripts/reinforcement_learning/sb3/train.py | 6 ++- scripts/reinforcement_learning/skrl/play.py | 7 ++- scripts/reinforcement_learning/skrl/train.py | 7 ++- source/isaaclab/docs/CHANGELOG.rst | 2 +- source/isaaclab/isaaclab/utils/recorder.py | 52 +++++++++---------- .../isaaclab_tasks/test/test_record_video.py | 6 ++- 14 files changed, 90 insertions(+), 40 deletions(-) diff --git a/scripts/benchmarks/benchmark_non_rl.py b/scripts/benchmarks/benchmark_non_rl.py index 861fac7ee7b..8d146ae3b16 100644 --- a/scripts/benchmarks/benchmark_non_rl.py +++ b/scripts/benchmarks/benchmark_non_rl.py @@ -81,14 +81,18 @@ import os import torch from datetime import datetime +from gymnasium.wrappers import RecordVideo from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + imports_time_end = time.perf_counter_ns() diff --git a/scripts/benchmarks/benchmark_rlgames.py b/scripts/benchmarks/benchmark_rlgames.py index c0647d4963d..e5eb7264bfe 100644 --- a/scripts/benchmarks/benchmark_rlgames.py +++ b/scripts/benchmarks/benchmark_rlgames.py @@ -68,6 +68,7 @@ import random import torch from datetime import datetime +from gymnasium.wrappers import RecordVideo from rl_games.common import env_configurations, vecenv from rl_games.common.algo_observer import IsaacAlgoObserver @@ -76,7 +77,7 @@ from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper @@ -87,6 +88,7 @@ sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../..")) + from isaaclab.utils.timer import Timer from scripts.benchmarks.utils import ( log_app_start_time, @@ -101,6 +103,9 @@ parse_tf_logs, ) +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + torch.backends.cuda.matmul.allow_tf32 = True torch.backends.cudnn.allow_tf32 = True torch.backends.cudnn.deterministic = False diff --git a/scripts/benchmarks/benchmark_rsl_rl.py b/scripts/benchmarks/benchmark_rsl_rl.py index 26d3e49fd83..8ea3baaaa35 100644 --- a/scripts/benchmarks/benchmark_rsl_rl.py +++ b/scripts/benchmarks/benchmark_rsl_rl.py @@ -70,13 +70,14 @@ import numpy as np import torch from datetime import datetime +from gymnasium.wrappers import RecordVideo from rsl_rl.runners import OnPolicyRunner from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlVecEnvWrapper @@ -89,6 +90,7 @@ from isaacsim.core.utils.extensions import enable_extension enable_extension("isaacsim.benchmark.services") + from isaacsim.benchmark.services import BaseIsaacBenchmark from isaaclab.utils.timer import Timer @@ -105,6 +107,9 @@ parse_tf_logs, ) +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + torch.backends.cuda.matmul.allow_tf32 = True torch.backends.cudnn.allow_tf32 = True torch.backends.cudnn.deterministic = False diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index e9280afcc17..3795607b1c7 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -60,6 +60,7 @@ import random import time import torch +from gymnasium.wrappers import RecordVideo from rl_games.common import env_configurations, vecenv from rl_games.common.player import BasePlayer @@ -75,7 +76,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper @@ -83,6 +84,9 @@ from isaaclab_tasks.utils import get_checkpoint_path from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index c5a008f7166..25b4ffd2004 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -64,6 +64,7 @@ import os import random from datetime import datetime +from gymnasium.wrappers import RecordVideo import omni from rl_games.common import env_configurations, vecenv @@ -80,13 +81,16 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index be50e7fae47..eb862458da7 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -57,6 +57,7 @@ import os import time import torch +from gymnasium.wrappers import RecordVideo from rsl_rl.runners import DistillationRunner, OnPolicyRunner @@ -70,7 +71,7 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rsl_rl import RslRlBaseRunnerCfg, RslRlVecEnvWrapper, export_policy_as_jit, export_policy_as_onnx @@ -78,6 +79,9 @@ from isaaclab_tasks.utils import get_checkpoint_path from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 9c07f0e1f5f..15e45fd9dbc 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -76,6 +76,7 @@ import os import torch from datetime import datetime +from gymnasium.wrappers import RecordVideo import omni from rsl_rl.runners import DistillationRunner, OnPolicyRunner @@ -89,7 +90,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.rsl_rl import RslRlBaseRunnerCfg, RslRlVecEnvWrapper @@ -97,6 +98,9 @@ from isaaclab_tasks.utils import get_checkpoint_path from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) torch.backends.cuda.matmul.allow_tf32 = True diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index d27bb8b704a..dd53fed7059 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -66,6 +66,7 @@ import random import time import torch +from gymnasium.wrappers import RecordVideo from stable_baselines3 import PPO from stable_baselines3.common.vec_env import VecNormalize @@ -79,7 +80,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.sb3 import Sb3VecEnvWrapper, process_sb3_cfg @@ -87,6 +88,9 @@ from isaaclab_tasks.utils.hydra import hydra_task_config from isaaclab_tasks.utils.parse_cfg import get_checkpoint_path +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index 30791721958..0186aa9954a 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -77,6 +77,7 @@ def cleanup_pbar(*args): import os import random from datetime import datetime +from gymnasium.wrappers import RecordVideo import omni from stable_baselines3 import PPO @@ -92,13 +93,16 @@ def cleanup_pbar(*args): ) from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.sb3 import Sb3VecEnvWrapper, process_sb3_cfg import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index fd24022c1fd..e12e9f7d8f3 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -79,6 +79,7 @@ import random import time import torch +from gymnasium.wrappers import RecordVideo import skrl from packaging import version @@ -97,6 +98,7 @@ elif args_cli.ml_framework.startswith("jax"): from skrl.utils.runner.jax import Runner + from isaaclab.envs import ( DirectMARLEnv, DirectMARLEnvCfg, @@ -106,7 +108,7 @@ ) from isaaclab.utils.dict import print_dict from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.skrl import SkrlVecEnvWrapper @@ -114,6 +116,9 @@ from isaaclab_tasks.utils import get_checkpoint_path from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) # config shortcuts diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index 201874c23a2..ad3bdf6d7e2 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -76,6 +76,7 @@ import os import random from datetime import datetime +from gymnasium.wrappers import RecordVideo import omni import skrl @@ -95,6 +96,7 @@ elif args_cli.ml_framework.startswith("jax"): from skrl.utils.runner.jax import Runner + from isaaclab.envs import ( DirectMARLEnv, DirectMARLEnvCfg, @@ -105,13 +107,16 @@ from isaaclab.utils.assets import retrieve_file_path from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_pickle, dump_yaml -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording from isaaclab_rl.skrl import SkrlVecEnvWrapper import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils.hydra import hydra_task_config +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + # PLACEHOLDER: Extension template (do not remove this comment) # config shortcuts diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 73a0d23e8aa..fd00a5b645c 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -7,7 +7,7 @@ Changelog Fixed ^^^^^ -* Fixed memory leak of gymnasium video recording wrapper in the :class:`~isaaclab.utils.recorder.RecordVideo` class. +* Fixed memory leak of gymnasium video recording wrapper by overwriting the :func:`~isaaclab.utils.recorder.RecordVideo` class. 0.45.12 (2025-09-05) diff --git a/source/isaaclab/isaaclab/utils/recorder.py b/source/isaaclab/isaaclab/utils/recorder.py index 7b943240116..6c2576348a1 100644 --- a/source/isaaclab/isaaclab/utils/recorder.py +++ b/source/isaaclab/isaaclab/utils/recorder.py @@ -3,42 +3,40 @@ # # SPDX-License-Identifier: BSD-3-Clause +"""Mokey-patch function to fix memory leak in gymnasium video recording wrapper. + +Should replace the stop_recording function in :class:`gymnasium.wrappers.RecordVideo` class.""" + from __future__ import annotations import gc -import gymnasium as gym import os from gymnasium import error, logger -class RecordVideo(gym.wrappers.RecordVideo): - """Fix gym wrapper to avoid memory leaks.""" - - def stop_recording(self): - """Stop current recording and saves the video.""" - assert self.recording, "stop_recording was called, but no recording was started" +def stop_recording(self): + """Stop current recording and saves the video.""" + assert self.recording, "stop_recording was called, but no recording was started" - if len(self.recorded_frames) == 0: - logger.warn("Ignored saving a video as there were zero frames to save.") - else: - try: - from moviepy.video.io.ImageSequenceClip import ImageSequenceClip - except ImportError as e: - raise error.DependencyNotInstalled( - 'MoviePy is not installed, run `pip install "gymnasium[other]"`' - ) from e + if len(self.recorded_frames) == 0: + logger.warn("Ignored saving a video as there were zero frames to save.") + else: + try: + from moviepy.video.io.ImageSequenceClip import ImageSequenceClip + except ImportError as e: + raise error.DependencyNotInstalled('MoviePy is not installed, run `pip install "gymnasium[other]"`') from e - clip = ImageSequenceClip(self.recorded_frames, fps=self.frames_per_sec) - moviepy_logger = None if self.disable_logger else "bar" - path = os.path.join(self.video_folder, f"{self._video_name}.mp4") - clip.write_videofile(path, logger=moviepy_logger) + clip = ImageSequenceClip(self.recorded_frames, fps=self.frames_per_sec) + moviepy_logger = None if self.disable_logger else "bar" + path = os.path.join(self.video_folder, f"{self._video_name}.mp4") + clip.write_videofile(path, logger=moviepy_logger) - del clip + del clip - del self.recorded_frames - self.recorded_frames = [] - self.recording = False - self._video_name = None + del self.recorded_frames + self.recorded_frames = [] + self.recording = False + self._video_name = None - if self.gc_trigger and self.gc_trigger(self.episode_id): - gc.collect() + if self.gc_trigger and self.gc_trigger(self.episode_id): + gc.collect() diff --git a/source/isaaclab_tasks/test/test_record_video.py b/source/isaaclab_tasks/test/test_record_video.py index a6cdde144d4..a4188c7c719 100644 --- a/source/isaaclab_tasks/test/test_record_video.py +++ b/source/isaaclab_tasks/test/test_record_video.py @@ -16,16 +16,20 @@ import gymnasium as gym import os import torch +from gymnasium.wrappers import RecordVideo import omni.usd import pytest from env_test_utils import setup_environment -from isaaclab.utils.recorder import RecordVideo +from isaaclab.utils.recorder import stop_recording import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import parse_env_cfg +# monkey-patch the stop_recording function to fix memory leak error (see https://github.com/Farama-Foundation/Gymnasium/pull/1444) +RecordVideo.stop_recording = stop_recording + @pytest.fixture(scope="function") def setup_video_params():