Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion source/isaaclab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.47.7"
version = "0.47.8"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
12 changes: 12 additions & 0 deletions source/isaaclab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,18 @@
Changelog
---------

0.47.8 (2025-11-05)
~~~~~~~~~~~~~~~~~~~

Changed
^^^^^^^

* Fixed termination term bookkeeping in :class:`~isaaclab.managers.TerminationManager`:
per-step termination and last-episode termination bookkeeping are now separated.
last-episode dones are now updated once per step from all term outputs, avoiding per-term overwrites
and ensuring Episode_Termination metrics reflect the actual triggering terms.


0.47.7 (2025-10-31)
~~~~~~~~~~~~~~~~~~~

Expand Down
19 changes: 12 additions & 7 deletions source/isaaclab/isaaclab/managers/termination_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,8 @@ def __init__(self, cfg: object, env: ManagerBasedRLEnv):
self._term_name_to_term_idx = {name: i for i, name in enumerate(self._term_names)}
# prepare extra info to store individual termination term information
self._term_dones = torch.zeros((self.num_envs, len(self._term_names)), device=self.device, dtype=torch.bool)
# prepare extra info to store last episode done per termination term information
self._last_episode_dones = torch.zeros_like(self._term_dones)
# create buffer for managing termination per environment
self._truncated_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.bool)
self._terminated_buf = torch.zeros_like(self._truncated_buf)
Expand Down Expand Up @@ -138,7 +140,7 @@ def reset(self, env_ids: Sequence[int] | None = None) -> dict[str, torch.Tensor]
env_ids = slice(None)
# add to episode dict
extras = {}
last_episode_done_stats = self._term_dones.float().mean(dim=0)
last_episode_done_stats = self._last_episode_dones.float().mean(dim=0)
for i, key in enumerate(self._term_names):
# store information
extras["Episode_Termination/" + key] = last_episode_done_stats[i].item()
Expand Down Expand Up @@ -169,15 +171,17 @@ def compute(self) -> torch.Tensor:
else:
self._terminated_buf |= value
# add to episode dones
rows = value.nonzero(as_tuple=True)[0] # indexing is cheaper than boolean advance indexing
if rows.numel() > 0:
self._term_dones[rows] = False
self._term_dones[rows, i] = True
self._term_dones[:, i] = value
# update last-episode dones once per compute: for any env where a term fired,
# reflect exactly which term(s) fired this step and clear others
rows = self._term_dones.any(dim=1).nonzero(as_tuple=True)[0]
if rows.numel() > 0:
self._last_episode_dones[rows] = self._term_dones[rows]
Comment on lines +177 to +179
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: When multiple terms fire for the same environment in one step, self._last_episode_dones[rows] = self._term_dones[rows] correctly captures all firing terms. However, when a different term fires in a subsequent step for the same environment before reset, this overwrites the previous term's record. For example:

  • Step 1: env 0 terminates due to term A → _last_episode_dones[0] = [True, False]
  • Step 2: env 0 terminates again due to term B → _last_episode_dones[0] = [False, True]
  • At reset: only term B is logged, term A is lost

This causes the logging to miss the original termination cause.

Comment on lines +177 to +179
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: Previous comment about overwriting is actually describing intended behavior. When term A fires at step 3 then term B fires at step 5 before reset, _last_episode_dones shows [False, True] (most recent). This is correct - test_term_transitions_and_persistence:101-106 validates this exact scenario. Multiple simultaneous terms in one step are captured correctly.

# return combined termination signal
return self._truncated_buf | self._terminated_buf

def get_term(self, name: str) -> torch.Tensor:
"""Returns the termination term with the specified name.
"""Returns the termination term value at current step with the specified name.

Args:
name: The name of the termination term.
Expand All @@ -190,7 +194,8 @@ def get_term(self, name: str) -> torch.Tensor:
def get_active_iterable_terms(self, env_idx: int) -> Sequence[tuple[str, Sequence[float]]]:
"""Returns the active terms as iterable sequence of tuples.

The first element of the tuple is the name of the term and the second element is the raw value(s) of the term.
The first element of the tuple is the name of the term and the second element is the raw value(s) of the term
recorded at current step.

Args:
env_idx: The specific environment to pull the active terms from.
Expand Down
140 changes: 140 additions & 0 deletions source/isaaclab/test/managers/test_termination_manager.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
# 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

"""Launch Isaac Sim Simulator first."""

from isaaclab.app import AppLauncher

# launch omniverse app
simulation_app = AppLauncher(headless=True).app

"""Rest everything follows."""

import torch

import pytest

from isaaclab.managers import TerminationManager, TerminationTermCfg
from isaaclab.sim import SimulationContext


class DummyEnv:
"""Minimal mutable env stub for the termination manager tests."""

def __init__(self, num_envs: int, device: str, sim: SimulationContext):
self.num_envs = num_envs
self.device = device
self.sim = sim
self.counter = 0 # mutable step counter used by test terms


def fail_every_5_steps(env) -> torch.Tensor:
"""Returns True for all envs when counter is a positive multiple of 5."""
cond = env.counter > 0 and (env.counter % 5 == 0)
return torch.full((env.num_envs,), cond, dtype=torch.bool, device=env.device)


def fail_every_10_steps(env) -> torch.Tensor:
"""Returns True for all envs when counter is a positive multiple of 10."""
cond = env.counter > 0 and (env.counter % 10 == 0)
return torch.full((env.num_envs,), cond, dtype=torch.bool, device=env.device)


def fail_every_3_steps(env) -> torch.Tensor:
"""Returns True for all envs when counter is a positive multiple of 3."""
cond = env.counter > 0 and (env.counter % 3 == 0)
return torch.full((env.num_envs,), cond, dtype=torch.bool, device=env.device)


@pytest.fixture
def env():
sim = SimulationContext()
return DummyEnv(num_envs=20, device="cpu", sim=sim)


def test_initial_state_and_shapes(env):
cfg = {
"term_5": TerminationTermCfg(func=fail_every_5_steps),
"term_10": TerminationTermCfg(func=fail_every_10_steps),
}
tm = TerminationManager(cfg, env)

# Active term names
assert tm.active_terms == ["term_5", "term_10"]

# Internal buffers have expected shapes and start as all False
assert tm._term_dones.shape == (env.num_envs, 2)
assert tm._last_episode_dones.shape == (env.num_envs, 2)
assert tm.dones.shape == (env.num_envs,)
assert tm.time_outs.shape == (env.num_envs,)
assert tm.terminated.shape == (env.num_envs,)
assert torch.all(~tm._term_dones) and torch.all(~tm._last_episode_dones)


def test_term_transitions_and_persistence(env):
"""Concise transitions: single fire, persist, switch, both, persist.

Uses 3-step and 5-step terms and verifies current-step values and last-episode persistence.
"""
cfg = {
"term_3": TerminationTermCfg(func=fail_every_3_steps, time_out=False),
"term_5": TerminationTermCfg(func=fail_every_5_steps, time_out=False),
}
tm = TerminationManager(cfg, env)

# step 3: only term_3 -> last_episode [True, False]
env.counter = 3
out = tm.compute()
assert torch.all(tm.get_term("term_3")) and torch.all(~tm.get_term("term_5"))
assert torch.all(out)
assert torch.all(tm._last_episode_dones[:, 0]) and torch.all(~tm._last_episode_dones[:, 1])

# step 4: none -> last_episode persists [True, False]
env.counter = 4
out = tm.compute()
assert torch.all(~out)
assert torch.all(~tm.get_term("term_3")) and torch.all(~tm.get_term("term_5"))
assert torch.all(tm._last_episode_dones[:, 0]) and torch.all(~tm._last_episode_dones[:, 1])

# step 5: only term_5 -> last_episode [False, True]
env.counter = 5
out = tm.compute()
assert torch.all(~tm.get_term("term_3")) and torch.all(tm.get_term("term_5"))
assert torch.all(out)
assert torch.all(~tm._last_episode_dones[:, 0]) and torch.all(tm._last_episode_dones[:, 1])

# step 15: both -> last_episode [True, True]
env.counter = 15
out = tm.compute()
assert torch.all(tm.get_term("term_3")) and torch.all(tm.get_term("term_5"))
assert torch.all(out)
assert torch.all(tm._last_episode_dones[:, 0]) and torch.all(tm._last_episode_dones[:, 1])

# step 16: none -> persist [True, True]
env.counter = 16
out = tm.compute()
assert torch.all(~out)
assert torch.all(~tm.get_term("term_3")) and torch.all(~tm.get_term("term_5"))
assert torch.all(tm._last_episode_dones[:, 0]) and torch.all(tm._last_episode_dones[:, 1])


def test_time_out_vs_terminated_split(env):
cfg = {
"term_5": TerminationTermCfg(func=fail_every_5_steps, time_out=False), # terminated
"term_10": TerminationTermCfg(func=fail_every_10_steps, time_out=True), # timeout
}
tm = TerminationManager(cfg, env)

# Step 5: terminated fires, not timeout
env.counter = 5
out = tm.compute()
assert torch.all(out)
assert torch.all(tm.terminated) and torch.all(~tm.time_outs)

# Step 10: both fire; timeout and terminated both True
env.counter = 10
out = tm.compute()
assert torch.all(out)
assert torch.all(tm.terminated) and torch.all(tm.time_outs)
Loading