diff --git a/mjlab/docs/source/_static/css/custom.css b/mjlab/docs/source/_static/css/custom.css new file mode 100644 index 0000000000000000000000000000000000000000..2a1adc86226e1e7ec5532ab03f492d74f4536114 --- /dev/null +++ b/mjlab/docs/source/_static/css/custom.css @@ -0,0 +1,172 @@ +/* + * PyData Sphinx Theme — Option A (Indigo/Teal) + * Aesthetic: modern lab — indigo primary, teal accent, neutral grays + */ + +/* LIGHT THEME */ +html[data-theme="light"] { + /* Brand */ + --pst-color-primary: #4F46E5; + /* Indigo-600 */ + --pst-color-secondary: #14B8A6; + /* Teal-500 */ + --pst-color-secondary-highlight: #2DD4BF; + /* Teal-400 */ + + /* Links / code links */ + --pst-color-inline-code-links: #0D9488; + /* Teal-600 */ + --pst-color-link: var(--pst-color-primary); + --pst-color-link-hover: #4338CA; + /* Indigo-700 */ + + /* Semantic */ + --pst-color-info: var(--pst-color-secondary); + --pst-color-info-highlight: var(--pst-color-secondary); + --pst-color-info-bg: #D1FAE5; + /* Teal-50 */ + --pst-color-attention: #F59E0B; + /* Amber-500 */ + --pst-color-target: #EEF2FF; + /* Indigo-50 */ + + /* Text */ + --pst-color-text-base: #1F2937; + /* Slate-800 */ + --pst-color-text-muted: #6B7280; + /* Slate-500 */ + + /* Surfaces */ + --pst-color-background: #FFFFFF; + --pst-color-on-background: #FFFFFF; + --pst-color-surface: #F3F4F6; + /* Gray-100 */ + --pst-color-on-surface: #E5E7EB; + /* Gray-200 */ + --pst-color-shadow: #D1D5DB; + --pst-color-border: #E5E7EB; + + /* Inline code */ + --pst-color-inline-code: #0D9488; + /* Teal-600 */ + + /* Tables / hovers */ + --pst-color-table-row-hover-bg: #EEF2FF; + /* Indigo-50 */ + + /* Accent (sparingly) */ + --pst-color-accent: #10B981; + /* Emerald-500 */ +} + +/* DARK THEME */ +html[data-theme="dark"] { + /* Brand */ + --pst-color-primary: #A5B4FC; + /* Indigo-300/200 mix for readability */ + --pst-color-secondary: #5EEAD4; + /* Teal-300 */ + --pst-color-secondary-highlight: #2DD4BF; + + /* Links / code links */ + --pst-color-inline-code-links: #93C5FD; + /* Indigo-300 */ + --pst-color-link: var(--pst-color-primary); + --pst-color-link-hover: #818CF8; + /* Indigo-400 */ + + /* Semantic */ + --pst-color-info: var(--pst-color-secondary); + --pst-color-info-highlight: var(--pst-color-secondary); + --pst-color-info-bg: #042F2E; + /* Deep teal */ + --pst-color-attention: #F59E0B; + --pst-color-target: #1B1C2A; + /* Indigo-tinted surface */ + + /* Text */ + --pst-color-text-base: #E5E7EB; + /* Gray-200 */ + --pst-color-text-muted: #9CA3AF; + /* Gray-400 */ + + /* Surfaces */ + --pst-color-background: #0B0C10; + /* Deep graphite */ + --pst-color-on-background: #12131A; + --pst-color-surface: #111827; + /* Slate-900 */ + --pst-color-on-surface: #1F2937; + /* Slate-800 */ + --pst-color-shadow: #0F172A; + --pst-color-border: #2A2D3A; + + /* Inline code */ + --pst-color-inline-code: #5EEAD4; + /* Teal-300 */ + + /* Tables / hovers */ + --pst-color-table-row-hover-bg: #1B1C2A; + + /* Accent */ + --pst-color-accent: #34D399; + /* Emerald-400 */ +} + +/* General tweaks */ +a { + text-decoration: none !important; +} + +.bd-header-announcement a, +.bd-header-version-warning a { + color: #5EEAD4; +} + +.form-control { + border-radius: 0 !important; + border: none !important; + outline: none !important; +} + +.navbar-brand, +.navbar-icon-links { + padding-top: 0rem !important; + padding-bottom: 0rem !important; +} + +/* Version switcher */ +.sidebar-version-switcher { + display: flex; + align-items: center; + gap: 0.5rem; + padding: 0.4rem 1rem; + margin-bottom: 0.5rem; +} + +.sidebar-version-label { + font-size: 0.8rem; + font-weight: 600; + color: var(--pst-color-text-muted); + white-space: nowrap; +} + +.sidebar-version-select { + flex: 1; + font-size: 0.8rem; + padding: 0.25rem 0.5rem; + border: 1px solid var(--pst-color-border); + border-radius: 4px; + background: var(--pst-color-background); + color: var(--pst-color-text-base); + cursor: pointer; +} + +.sidebar-version-select:hover { + border-color: var(--pst-color-primary); +} + +/* Sidebar section spacing */ +.bd-sidebar .navbar-icon-links { + padding: 0 1rem 0.25rem !important; +} \ No newline at end of file diff --git a/mjlab/docs/source/_static/favicon.ico b/mjlab/docs/source/_static/favicon.ico new file mode 100644 index 0000000000000000000000000000000000000000..2f9ce5c4e106bf3c7031b792cf140380a2b9830d Binary files /dev/null and b/mjlab/docs/source/_static/favicon.ico differ diff --git a/mjlab/docs/source/_static/refs.bib b/mjlab/docs/source/_static/refs.bib new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/mjlab/docs/source/api/actuator.rst b/mjlab/docs/source/api/actuator.rst new file mode 100644 index 0000000000000000000000000000000000000000..5969d9bb3813812f568012f2b3e79fc81905b21c --- /dev/null +++ b/mjlab/docs/source/api/actuator.rst @@ -0,0 +1,10 @@ +mjlab.actuator +============== + +Actuator implementations for motor control. + +.. automodule:: mjlab.actuator + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/entity.rst b/mjlab/docs/source/api/entity.rst new file mode 100644 index 0000000000000000000000000000000000000000..cd4ad5ca1c78486eb92370a01b1d80078a37926c --- /dev/null +++ b/mjlab/docs/source/api/entity.rst @@ -0,0 +1,10 @@ +mjlab.entity +============ + +Entity models and data structures. + +.. automodule:: mjlab.entity + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/envs.rst b/mjlab/docs/source/api/envs.rst new file mode 100644 index 0000000000000000000000000000000000000000..a797439ae914ad6f51906a323192e852a80f7a2e --- /dev/null +++ b/mjlab/docs/source/api/envs.rst @@ -0,0 +1,10 @@ +mjlab.envs +========== + +RL environment classes. + +.. automodule:: mjlab.envs + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/index.rst b/mjlab/docs/source/api/index.rst new file mode 100644 index 0000000000000000000000000000000000000000..ef4cbb3f6ec061adacae6bb12be19fbae5ef385c --- /dev/null +++ b/mjlab/docs/source/api/index.rst @@ -0,0 +1,16 @@ +API Reference +============= + +This section provides detailed API documentation for all public modules in mjlab. + +.. toctree:: + :maxdepth: 1 + + envs + scene + sim + entity + actuator + sensor + managers + terrains diff --git a/mjlab/docs/source/api/managers.rst b/mjlab/docs/source/api/managers.rst new file mode 100644 index 0000000000000000000000000000000000000000..74ba73955d7138b5eea295745a74d0cdc5174fc4 --- /dev/null +++ b/mjlab/docs/source/api/managers.rst @@ -0,0 +1,10 @@ +mjlab.managers +============== + +Environment managers for actions, observations, rewards, terminations, commands, and curriculum. + +.. automodule:: mjlab.managers + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/scene.rst b/mjlab/docs/source/api/scene.rst new file mode 100644 index 0000000000000000000000000000000000000000..4e6220dcb16e38d1c15e7db5b5a5e3cab2c722ae --- /dev/null +++ b/mjlab/docs/source/api/scene.rst @@ -0,0 +1,10 @@ +mjlab.scene +=========== + +Scene management. + +.. automodule:: mjlab.scene + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/sensor.rst b/mjlab/docs/source/api/sensor.rst new file mode 100644 index 0000000000000000000000000000000000000000..05f497b1a8f4fb7609ea7efb517da6f5ae2c7778 --- /dev/null +++ b/mjlab/docs/source/api/sensor.rst @@ -0,0 +1,10 @@ +mjlab.sensor +============ + +Sensor implementations. + +.. automodule:: mjlab.sensor + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/sim.rst b/mjlab/docs/source/api/sim.rst new file mode 100644 index 0000000000000000000000000000000000000000..245d3b23a69e40f318feb8a2268bb9e81fe7007d --- /dev/null +++ b/mjlab/docs/source/api/sim.rst @@ -0,0 +1,10 @@ +mjlab.sim +========= + +Simulation core. + +.. automodule:: mjlab.sim + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/docs/source/api/terrains.rst b/mjlab/docs/source/api/terrains.rst new file mode 100644 index 0000000000000000000000000000000000000000..3609c355689127052447806d136778f037e739c4 --- /dev/null +++ b/mjlab/docs/source/api/terrains.rst @@ -0,0 +1,10 @@ +mjlab.terrains +============== + +Terrain generation and importing. + +.. automodule:: mjlab.terrains + :members: + :undoc-members: + :imported-members: + :show-inheritance: diff --git a/mjlab/src/mjlab/__init__.py b/mjlab/src/mjlab/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e34aee4fbdd78a1b92ad8f09ed8daceec3c92d7b --- /dev/null +++ b/mjlab/src/mjlab/__init__.py @@ -0,0 +1,59 @@ +import os +from importlib.metadata import entry_points +from pathlib import Path + +import tyro +import warp as wp + +MJLAB_SRC_PATH: Path = Path(__file__).parent + +TYRO_FLAGS = ( + # Don't let users switch between types in unions. This produces a simpler CLI + # with flatter helptext, at the cost of some flexibility. Type changes can + # just be done in code. + tyro.conf.AvoidSubcommands, + # Disable automatic flag conversion (e.g., use `--flag False` instead of + # `--no-flag` for booleans). + tyro.conf.FlagConversionOff, + # Use Python syntax for collections: --tuple (1,2,3) instead of --tuple 1 2 3. + # Helps with wandb sweep compatibility: https://brentyi.github.io/tyro/wandb_sweeps/ + tyro.conf.UsePythonSyntaxForLiteralCollections, +) + + +def _configure_warp() -> None: + """Configure Warp globally for mjlab.""" + wp.config.enable_backward = False + + # Keep warp verbose by default to show kernel compilation progress. + # Override with MJLAB_WARP_QUIET=1 environment variable if needed. + quiet = os.environ.get("MJLAB_WARP_QUIET", "0").lower() in ("1", "true", "yes") + wp.config.quiet = quiet + + +def _import_registered_packages() -> None: + """Auto-discover and import packages registered via entry points. + + Looks for packages registered under the 'mjlab.tasks' entry point group. + Each discovered package is imported, which allows it to register custom + environments with gymnasium. + """ + mjlab_tasks = entry_points().select(group="mjlab.tasks") + for entry_point in mjlab_tasks: + try: + entry_point.load() + except Exception as e: + print(f"[WARN] Failed to load task package {entry_point.name}: {e}") + + +def _configure_mediapy() -> None: + """Point mediapy at the bundled imageio-ffmpeg binary.""" + import imageio_ffmpeg + import mediapy + + mediapy.set_ffmpeg(imageio_ffmpeg.get_ffmpeg_exe()) + + +_configure_warp() +_configure_mediapy() +_import_registered_packages() diff --git a/mjlab/src/mjlab/actuator/__init__.py b/mjlab/src/mjlab/actuator/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..20d453efbfebdcbbaf45d74ceb7ea3fa9e15c955 --- /dev/null +++ b/mjlab/src/mjlab/actuator/__init__.py @@ -0,0 +1,48 @@ +"""Actuator implementations for mjlab.""" + +from mjlab.actuator.actuator import Actuator as Actuator +from mjlab.actuator.actuator import ActuatorCfg as ActuatorCfg +from mjlab.actuator.actuator import ActuatorCmd as ActuatorCmd +from mjlab.actuator.builtin_actuator import ( + BuiltinMotorActuator as BuiltinMotorActuator, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinMotorActuatorCfg as BuiltinMotorActuatorCfg, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinMuscleActuator as BuiltinMuscleActuator, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinMuscleActuatorCfg as BuiltinMuscleActuatorCfg, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinPositionActuator as BuiltinPositionActuator, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinPositionActuatorCfg as BuiltinPositionActuatorCfg, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinVelocityActuator as BuiltinVelocityActuator, +) +from mjlab.actuator.builtin_actuator import ( + BuiltinVelocityActuatorCfg as BuiltinVelocityActuatorCfg, +) +from mjlab.actuator.builtin_group import BuiltinActuatorGroup as BuiltinActuatorGroup +from mjlab.actuator.dc_actuator import DcMotorActuator as DcMotorActuator +from mjlab.actuator.dc_actuator import DcMotorActuatorCfg as DcMotorActuatorCfg +from mjlab.actuator.delayed_actuator import DelayedActuator as DelayedActuator +from mjlab.actuator.delayed_actuator import DelayedActuatorCfg as DelayedActuatorCfg +from mjlab.actuator.learned_actuator import LearnedMlpActuator as LearnedMlpActuator +from mjlab.actuator.learned_actuator import ( + LearnedMlpActuatorCfg as LearnedMlpActuatorCfg, +) +from mjlab.actuator.pd_actuator import IdealPdActuator as IdealPdActuator +from mjlab.actuator.pd_actuator import IdealPdActuatorCfg as IdealPdActuatorCfg +from mjlab.actuator.xml_actuator import XmlMotorActuator as XmlMotorActuator +from mjlab.actuator.xml_actuator import XmlMotorActuatorCfg as XmlMotorActuatorCfg +from mjlab.actuator.xml_actuator import XmlMuscleActuator as XmlMuscleActuator +from mjlab.actuator.xml_actuator import XmlMuscleActuatorCfg as XmlMuscleActuatorCfg +from mjlab.actuator.xml_actuator import XmlPositionActuator as XmlPositionActuator +from mjlab.actuator.xml_actuator import XmlPositionActuatorCfg as XmlPositionActuatorCfg +from mjlab.actuator.xml_actuator import XmlVelocityActuator as XmlVelocityActuator +from mjlab.actuator.xml_actuator import XmlVelocityActuatorCfg as XmlVelocityActuatorCfg diff --git a/mjlab/src/mjlab/actuator/actuator.py b/mjlab/src/mjlab/actuator/actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..1f1c4340e0d194f84031dbb42a1d20fec28ebb0e --- /dev/null +++ b/mjlab/src/mjlab/actuator/actuator.py @@ -0,0 +1,269 @@ +"""Base actuator interface.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from dataclasses import dataclass +from enum import Enum +from typing import TYPE_CHECKING, Generic, TypeVar + +import mujoco +import mujoco_warp as mjwarp +import torch + +if TYPE_CHECKING: + from mjlab.entity import Entity + from mjlab.entity.data import EntityData + +ActuatorCfgT = TypeVar("ActuatorCfgT", bound="ActuatorCfg") + + +class TransmissionType(str, Enum): + """Transmission types for actuators.""" + + JOINT = "joint" + TENDON = "tendon" + SITE = "site" + + +@dataclass(kw_only=True) +class ActuatorCfg(ABC): + target_names_expr: tuple[str, ...] + """Targets that are part of this actuator group. + + Can be a tuple of names or tuple of regex expressions. + Interpreted based on transmission_type (joint/tendon/site). + """ + + transmission_type: TransmissionType = TransmissionType.JOINT + """Transmission type. Defaults to JOINT.""" + + armature: float = 0.0 + """Reflected rotor inertia.""" + + frictionloss: float = 0.0 + """Friction loss force limit. + + Applies a constant friction force opposing motion, independent of load or velocity. + Also known as dry friction or load-independent friction. + """ + + def __post_init__(self) -> None: + assert self.armature >= 0.0, "armature must be non-negative." + assert self.frictionloss >= 0.0, "frictionloss must be non-negative." + if self.transmission_type == TransmissionType.SITE: + if self.armature > 0.0 or self.frictionloss > 0.0: + raise ValueError( + f"{self.__class__.__name__}: armature and frictionloss are not supported for " + "SITE transmission type." + ) + + @abstractmethod + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> Actuator: + """Build actuator instance. + + Args: + entity: Entity this actuator belongs to. + target_ids: Local target indices (for indexing entity arrays). + target_names: Target names corresponding to target_ids. + + Returns: + Actuator instance. + """ + raise NotImplementedError + + +@dataclass +class ActuatorCmd: + """High-level actuator command with targets and current state. + + Passed to actuator's `compute()` method to generate low-level control signals. + All tensors have shape (num_envs, num_targets). + """ + + position_target: torch.Tensor + """Desired positions (joint positions, tendon lengths, or site positions).""" + velocity_target: torch.Tensor + """Desired velocities (joint velocities, tendon velocities, or site velocities).""" + effort_target: torch.Tensor + """Feedforward effort (torques or forces).""" + pos: torch.Tensor + """Current positions (joint positions, tendon lengths, or site positions).""" + vel: torch.Tensor + """Current velocities (joint velocities, tendon velocities, or site velocities).""" + + +class Actuator(ABC, Generic[ActuatorCfgT]): + """Base actuator interface.""" + + def __init__( + self, + cfg: ActuatorCfgT, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + self.cfg = cfg + self.entity = entity + self._target_ids_list = target_ids + self._target_names = target_names + self._target_ids: torch.Tensor | None = None + self._ctrl_ids: torch.Tensor | None = None + self._global_ctrl_ids: torch.Tensor | None = None + self._mjs_actuators: list[mujoco.MjsActuator] = [] + self._site_zeros: torch.Tensor | None = None + + @property + def target_ids(self) -> torch.Tensor: + """Local indices of targets controlled by this actuator.""" + assert self._target_ids is not None + return self._target_ids + + @property + def target_names(self) -> list[str]: + """Names of targets controlled by this actuator.""" + return self._target_names + + @property + def transmission_type(self) -> TransmissionType: + """Transmission type of this actuator.""" + return self.cfg.transmission_type + + @property + def ctrl_ids(self) -> torch.Tensor: + """Local indices of control inputs within the entity.""" + assert self._ctrl_ids is not None + return self._ctrl_ids + + @property + def global_ctrl_ids(self) -> torch.Tensor: + """Global indices of control inputs in the MuJoCo model.""" + assert self._global_ctrl_ids is not None + return self._global_ctrl_ids + + @abstractmethod + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + """Edit the MjSpec to add actuators. + + This is called during entity construction, before the model is compiled. + + Args: + spec: The entity's MjSpec to edit. + target_names: Names of targets (joints, tendons, or sites) controlled by + this actuator. + """ + raise NotImplementedError + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + """Initialize the actuator after model compilation. + + This is called after the MjSpec is compiled into an MjModel. + + Args: + mj_model: The compiled MuJoCo model. + model: The compiled mjwarp model. + data: The mjwarp data arrays. + device: Device for tensor operations (e.g., "cuda", "cpu"). + """ + del mj_model, model # Unused. + self._target_ids = torch.tensor( + self._target_ids_list, dtype=torch.long, device=device + ) + global_ctrl_ids_list = [act.id for act in self._mjs_actuators] + self._global_ctrl_ids = torch.tensor( + global_ctrl_ids_list, dtype=torch.long, device=device + ) + entity_ctrl_ids = self.entity.indexing.ctrl_ids + global_to_local = {gid.item(): i for i, gid in enumerate(entity_ctrl_ids)} + self._ctrl_ids = torch.tensor( + [global_to_local[gid] for gid in global_ctrl_ids_list], + dtype=torch.long, + device=device, + ) + + # Pre-allocate zeros for SITE transmission type to avoid repeated allocations. + if self.transmission_type == TransmissionType.SITE: + nenvs = data.nworld + ntargets = len(self._target_ids_list) + self._site_zeros = torch.zeros((nenvs, ntargets), device=device) + + def get_command(self, data: EntityData) -> ActuatorCmd: + """Extract command data for this actuator from entity data. + + Args: + data: The entity data containing all state and target information. + + Returns: + ActuatorCmd with appropriate data based on transmission type. + """ + if self.transmission_type == TransmissionType.JOINT: + return ActuatorCmd( + position_target=data.joint_pos_target[:, self.target_ids], + velocity_target=data.joint_vel_target[:, self.target_ids], + effort_target=data.joint_effort_target[:, self.target_ids], + pos=data.joint_pos[:, self.target_ids], + vel=data.joint_vel[:, self.target_ids], + ) + elif self.transmission_type == TransmissionType.TENDON: + return ActuatorCmd( + position_target=data.tendon_len_target[:, self.target_ids], + velocity_target=data.tendon_vel_target[:, self.target_ids], + effort_target=data.tendon_effort_target[:, self.target_ids], + pos=data.tendon_len[:, self.target_ids], + vel=data.tendon_vel[:, self.target_ids], + ) + elif self.transmission_type == TransmissionType.SITE: + assert self._site_zeros is not None + return ActuatorCmd( + position_target=self._site_zeros, + velocity_target=self._site_zeros, + effort_target=data.site_effort_target[:, self.target_ids], + pos=self._site_zeros, + vel=self._site_zeros, + ) + else: + raise ValueError(f"Unknown transmission type: {self.transmission_type}") + + @abstractmethod + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + """Compute low-level actuator control signal from high-level commands. + + Args: + cmd: High-level actuator command. + + Returns: + Control signal tensor of shape (num_envs, num_actuators). + """ + raise NotImplementedError + + # Optional methods. + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + """Reset actuator state for specified environments. + + Base implementation does nothing. Override in subclasses that maintain + internal state. + + Args: + env_ids: Environment indices to reset. If None, reset all environments. + """ + del env_ids # Unused. + + def update(self, dt: float) -> None: + """Update actuator state after a simulation step. + + Base implementation does nothing. Override in subclasses that need + per-step updates. + + Args: + dt: Time step in seconds. + """ + del dt # Unused. diff --git a/mjlab/src/mjlab/actuator/builtin_actuator.py b/mjlab/src/mjlab/actuator/builtin_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..c0172db46a74b3da071187d68a3d21928623ab3b --- /dev/null +++ b/mjlab/src/mjlab/actuator/builtin_actuator.py @@ -0,0 +1,279 @@ +"""MuJoCo built-in actuators. + +This module provides actuators that use MuJoCo's native actuator implementations, +created programmatically via the MjSpec API. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING + +import mujoco +import torch + +from mjlab.actuator.actuator import ( + Actuator, + ActuatorCfg, + ActuatorCmd, + TransmissionType, +) +from mjlab.utils.spec import ( + create_motor_actuator, + create_muscle_actuator, + create_position_actuator, + create_velocity_actuator, +) + +if TYPE_CHECKING: + from mjlab.entity import Entity + + +@dataclass(kw_only=True) +class BuiltinPositionActuatorCfg(ActuatorCfg): + """Configuration for MuJoCo built-in position actuator. + + Under the hood, this creates a actuator for each target and sets + the stiffness, damping and effort limits accordingly. It also modifies the target's + properties, namely armature and frictionloss. + """ + + stiffness: float + """PD proportional gain.""" + damping: float + """PD derivative gain.""" + effort_limit: float | None = None + """Maximum actuator force/torque. If None, no limit is applied.""" + + def __post_init__(self) -> None: + super().__post_init__() + if self.transmission_type == TransmissionType.SITE: + raise ValueError( + "BuiltinPositionActuatorCfg does not support SITE transmission. " + "Use BuiltinMotorActuatorCfg for site transmission." + ) + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> BuiltinPositionActuator: + return BuiltinPositionActuator(self, entity, target_ids, target_names) + + +class BuiltinPositionActuator(Actuator[BuiltinPositionActuatorCfg]): + """MuJoCo built-in position actuator.""" + + def __init__( + self, + cfg: BuiltinPositionActuatorCfg, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Add actuator to spec, one per target. + for target_name in target_names: + actuator = create_position_actuator( + spec, + target_name, + stiffness=self.cfg.stiffness, + damping=self.cfg.damping, + effort_limit=self.cfg.effort_limit, + armature=self.cfg.armature, + frictionloss=self.cfg.frictionloss, + transmission_type=self.cfg.transmission_type, + ) + self._mjs_actuators.append(actuator) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.position_target + + +@dataclass(kw_only=True) +class BuiltinMotorActuatorCfg(ActuatorCfg): + """Configuration for MuJoCo built-in motor actuator. + + Under the hood, this creates a actuator for each target and sets + its effort limit and gear ratio accordingly. It also modifies the target's + properties, namely armature and frictionloss. + """ + + effort_limit: float + """Maximum actuator effort.""" + gear: float = 1.0 + """Actuator gear ratio.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> BuiltinMotorActuator: + return BuiltinMotorActuator(self, entity, target_ids, target_names) + + +class BuiltinMotorActuator(Actuator[BuiltinMotorActuatorCfg]): + """MuJoCo built-in motor actuator.""" + + def __init__( + self, + cfg: BuiltinMotorActuatorCfg, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Add actuator to spec, one per target. + for target_name in target_names: + actuator = create_motor_actuator( + spec, + target_name, + effort_limit=self.cfg.effort_limit, + gear=self.cfg.gear, + armature=self.cfg.armature, + frictionloss=self.cfg.frictionloss, + transmission_type=self.cfg.transmission_type, + ) + self._mjs_actuators.append(actuator) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.effort_target + + +@dataclass(kw_only=True) +class BuiltinVelocityActuatorCfg(ActuatorCfg): + """Configuration for MuJoCo built-in velocity actuator. + + Under the hood, this creates a actuator for each target and sets the + damping gain. It also modifies the target's properties, namely armature and + frictionloss. + """ + + damping: float + """Damping gain.""" + effort_limit: float | None = None + """Maximum actuator force/torque. If None, no limit is applied.""" + + def __post_init__(self) -> None: + super().__post_init__() + if self.transmission_type == TransmissionType.SITE: + raise ValueError( + "BuiltinVelocityActuatorCfg does not support SITE transmission. " + "Use BuiltinMotorActuatorCfg for site transmission." + ) + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> BuiltinVelocityActuator: + return BuiltinVelocityActuator(self, entity, target_ids, target_names) + + +class BuiltinVelocityActuator(Actuator[BuiltinVelocityActuatorCfg]): + """MuJoCo built-in velocity actuator.""" + + def __init__( + self, + cfg: BuiltinVelocityActuatorCfg, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Add actuator to spec, one per target. + for target_name in target_names: + actuator = create_velocity_actuator( + spec, + target_name, + damping=self.cfg.damping, + effort_limit=self.cfg.effort_limit, + armature=self.cfg.armature, + frictionloss=self.cfg.frictionloss, + transmission_type=self.cfg.transmission_type, + ) + self._mjs_actuators.append(actuator) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.velocity_target + + +@dataclass(kw_only=True) +class BuiltinMuscleActuatorCfg(ActuatorCfg): + """Configuration for MuJoCo built-in muscle actuator.""" + + length_range: tuple[float, float] = (0.0, 0.0) + """Length range for muscle actuator.""" + gear: float = 1.0 + """Gear ratio.""" + timeconst: tuple[float, float] = (0.01, 0.04) + """Activation and deactivation time constants.""" + tausmooth: float = 0.0 + """Smoothing time constant.""" + range: tuple[float, float] = (0.75, 1.05) + """Operating range of normalized muscle length.""" + force: float = -1.0 + """Peak force (if -1, defaults to scale * FLV).""" + scale: float = 200.0 + """Force scaling factor.""" + lmin: float = 0.5 + """Minimum normalized muscle length.""" + lmax: float = 1.6 + """Maximum normalized muscle length.""" + vmax: float = 1.5 + """Maximum normalized muscle velocity.""" + fpmax: float = 1.3 + """Passive force at lmax.""" + fvmax: float = 1.2 + """Active force at -vmax.""" + + def __post_init__(self) -> None: + super().__post_init__() + if self.transmission_type == TransmissionType.SITE: + raise ValueError( + "BuiltinMuscleActuatorCfg does not support SITE transmission. " + "Use BuiltinMotorActuatorCfg for site transmission." + ) + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> BuiltinMuscleActuator: + return BuiltinMuscleActuator(self, entity, target_ids, target_names) + + +class BuiltinMuscleActuator(Actuator[BuiltinMuscleActuatorCfg]): + """MuJoCo built-in muscle actuator.""" + + def __init__( + self, + cfg: BuiltinMuscleActuatorCfg, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Add actuator to spec, one per target. + for target_name in target_names: + actuator = create_muscle_actuator( + spec, + target_name, + length_range=self.cfg.length_range, + gear=self.cfg.gear, + timeconst=self.cfg.timeconst, + tausmooth=self.cfg.tausmooth, + range=self.cfg.range, + force=self.cfg.force, + scale=self.cfg.scale, + lmin=self.cfg.lmin, + lmax=self.cfg.lmax, + vmax=self.cfg.vmax, + fpmax=self.cfg.fpmax, + fvmax=self.cfg.fvmax, + transmission_type=self.cfg.transmission_type, + ) + self._mjs_actuators.append(actuator) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.effort_target diff --git a/mjlab/src/mjlab/actuator/builtin_group.py b/mjlab/src/mjlab/actuator/builtin_group.py new file mode 100644 index 0000000000000000000000000000000000000000..ad14705e7aa6ef1d5f0c4043d76ffb9b9e84e5d2 --- /dev/null +++ b/mjlab/src/mjlab/actuator/builtin_group.py @@ -0,0 +1,112 @@ +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING + +import torch + +from mjlab.actuator.actuator import TransmissionType +from mjlab.actuator.builtin_actuator import ( + BuiltinMotorActuator, + BuiltinMuscleActuator, + BuiltinPositionActuator, + BuiltinVelocityActuator, +) + +if TYPE_CHECKING: + from mjlab.actuator.actuator import Actuator + from mjlab.entity.data import EntityData + +BuiltinActuatorType = ( + BuiltinMotorActuator + | BuiltinMuscleActuator + | BuiltinPositionActuator + | BuiltinVelocityActuator +) + +# Maps (actuator_type, transmission_type) to EntityData target tensor attribute name. +_TARGET_TENSOR_MAP: dict[tuple[type[BuiltinActuatorType], TransmissionType], str] = { + (BuiltinPositionActuator, TransmissionType.JOINT): "joint_pos_target", + (BuiltinVelocityActuator, TransmissionType.JOINT): "joint_vel_target", + (BuiltinMotorActuator, TransmissionType.JOINT): "joint_effort_target", + (BuiltinPositionActuator, TransmissionType.TENDON): "tendon_len_target", + (BuiltinVelocityActuator, TransmissionType.TENDON): "tendon_vel_target", + (BuiltinMotorActuator, TransmissionType.TENDON): "tendon_effort_target", + (BuiltinMotorActuator, TransmissionType.SITE): "site_effort_target", + (BuiltinMuscleActuator, TransmissionType.JOINT): "joint_effort_target", + (BuiltinMuscleActuator, TransmissionType.TENDON): "tendon_effort_target", +} + + +@dataclass(frozen=True) +class BuiltinActuatorGroup: + """Groups builtin actuators for batch processing. + + Builtin actuators (position, velocity, motor) just pass through target values + from entity data to control signals. This class pre-computes the mappings and + enables direct writes without per-actuator overhead. + """ + + # Map from (BuiltinActuator type, transmission_type) to (target_ids, ctrl_ids). + _index_groups: dict[ + tuple[type[BuiltinActuatorType], TransmissionType], + tuple[torch.Tensor, torch.Tensor], + ] + + @staticmethod + def process( + actuators: list[Actuator], + ) -> tuple[BuiltinActuatorGroup, tuple[Actuator, ...]]: + """Register builtin actuators and pre-compute their mappings. + + Args: + actuators: List of initialized actuators to process. + + Returns: + A tuple containing: + - BuiltinActuatorGroup with pre-computed mappings. + - List of custom (non-builtin) actuators. + """ + + builtin_groups: dict[ + tuple[type[BuiltinActuatorType], TransmissionType], list[Actuator] + ] = {} + custom_actuators: list[Actuator] = [] + + # Group actuators by (type, transmission_type). + for act in actuators: + if isinstance(act, BuiltinActuatorType): + key: tuple[type[BuiltinActuatorType], TransmissionType] = ( + type(act), + act.cfg.transmission_type, + ) + builtin_groups.setdefault(key, []).append(act) + else: + custom_actuators.append(act) + + # Return stacked indices for each (actuator_type, transmission_type) group. + index_groups: dict[ + tuple[type[BuiltinActuatorType], TransmissionType], + tuple[torch.Tensor, torch.Tensor], + ] = { + key: ( + torch.cat([act.target_ids for act in acts], dim=0), + torch.cat([act.ctrl_ids for act in acts], dim=0), + ) + for key, acts in builtin_groups.items() + } + return BuiltinActuatorGroup(index_groups), tuple(custom_actuators) + + def apply_controls(self, data: EntityData) -> None: + """Write builtin actuator controls directly to simulation data. + + Args: + data: Entity data containing targets and control arrays. + """ + for (actuator_type, transmission_type), ( + target_ids, + ctrl_ids, + ) in self._index_groups.items(): + attr_name = _TARGET_TENSOR_MAP[(actuator_type, transmission_type)] + target_tensor = getattr(data, attr_name) + data.write_ctrl(target_tensor[:, target_ids], ctrl_ids) diff --git a/mjlab/src/mjlab/actuator/dc_actuator.py b/mjlab/src/mjlab/actuator/dc_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..96b555aa6da891d1981cf3c089f0681be82fee43 --- /dev/null +++ b/mjlab/src/mjlab/actuator/dc_actuator.py @@ -0,0 +1,162 @@ +"""DC motor actuator with velocity-based saturation model. + +This module provides a DC motor actuator that implements a realistic torque-speed +curve for more accurate motor behavior simulation. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Generic, TypeVar + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.actuator.actuator import ActuatorCmd +from mjlab.actuator.pd_actuator import IdealPdActuator, IdealPdActuatorCfg + +if TYPE_CHECKING: + from mjlab.entity import Entity + +DcMotorCfgT = TypeVar("DcMotorCfgT", bound="DcMotorActuatorCfg") + + +@dataclass(kw_only=True) +class DcMotorActuatorCfg(IdealPdActuatorCfg): + """Configuration for DC motor actuator with velocity-based saturation. + + This actuator implements a DC motor torque-speed curve for more realistic + actuator behavior. The motor produces maximum torque (saturation_effort) at + zero velocity and reduces linearly to zero torque at maximum velocity. + + Note: effort_limit should be explicitly set to a realistic value for proper + motor modeling. Using the default (inf) will trigger a warning. Use + IdealPdActuator if unlimited torque is desired. + """ + + saturation_effort: float + """Peak motor torque at zero velocity (stall torque).""" + + velocity_limit: float + """Maximum motor velocity (no-load speed).""" + + def __post_init__(self) -> None: + """Validate DC motor parameters.""" + import warnings + + if self.effort_limit == float("inf"): + warnings.warn( + "effort_limit is set to inf for DcMotorActuator, which creates an " + "unrealistic motor with unlimited continuous torque. Consider setting " + "effort_limit to your motor's continuous rating (<= saturation_effort). " + "Use IdealPdActuator if you truly want unlimited torque.", + UserWarning, + stacklevel=2, + ) + + if self.effort_limit > self.saturation_effort: + warnings.warn( + f"effort_limit ({self.effort_limit}) exceeds saturation_effort " + f"({self.saturation_effort}). For realistic motors, continuous torque " + "should be <= peak torque.", + UserWarning, + stacklevel=2, + ) + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> DcMotorActuator: + return DcMotorActuator(self, entity, target_ids, target_names) + + +class DcMotorActuator(IdealPdActuator[DcMotorCfgT], Generic[DcMotorCfgT]): + """DC motor actuator with velocity-based saturation model. + + This actuator extends IdealPdActuator with a realistic DC motor model + that limits torque based on current joint velocity. The model implements + a linear torque-speed curve where: + - At zero velocity: can produce full saturation_effort (stall torque) + - At max velocity: can produce zero torque + - Between: torque limit varies linearly + + The continuous torque limit (effort_limit) further constrains the output. + """ + + def __init__( + self, + cfg: DcMotorCfgT, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + self.saturation_effort: torch.Tensor | None = None + self.velocity_limit_motor: torch.Tensor | None = None + self._vel_at_effort_lim: torch.Tensor | None = None + self._joint_vel_clipped: torch.Tensor | None = None + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + super().initialize(mj_model, model, data, device) + + num_envs = data.nworld + num_joints = len(self._target_names) + + self.saturation_effort = torch.full( + (num_envs, num_joints), + self.cfg.saturation_effort, + dtype=torch.float, + device=device, + ) + self.velocity_limit_motor = torch.full( + (num_envs, num_joints), + self.cfg.velocity_limit, + dtype=torch.float, + device=device, + ) + + # Compute corner velocity where torque-speed curve intersects effort_limit. + assert self.force_limit is not None + self._vel_at_effort_lim = self.velocity_limit_motor * ( + 1 + self.force_limit / self.saturation_effort + ) + self._joint_vel_clipped = torch.zeros(num_envs, num_joints, device=device) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + assert self._joint_vel_clipped is not None + self._joint_vel_clipped[:] = cmd.vel + return super().compute(cmd) + + def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor: + assert self.saturation_effort is not None + assert self.velocity_limit_motor is not None + assert self.force_limit is not None + assert self._vel_at_effort_lim is not None + assert self._joint_vel_clipped is not None + + # Clip velocity to corner velocity range. + vel_clipped = torch.clamp( + self._joint_vel_clipped, + min=-self._vel_at_effort_lim, + max=self._vel_at_effort_lim, + ) + + # Compute torque-speed curve limits. + torque_speed_top = self.saturation_effort * ( + 1.0 - vel_clipped / self.velocity_limit_motor + ) + torque_speed_bottom = self.saturation_effort * ( + -1.0 - vel_clipped / self.velocity_limit_motor + ) + + # Apply continuous torque constraint. + max_effort = torch.clamp(torque_speed_top, max=self.force_limit) + min_effort = torch.clamp(torque_speed_bottom, min=-self.force_limit) + + return torch.clamp(effort, min=min_effort, max=max_effort) diff --git a/mjlab/src/mjlab/actuator/delayed_actuator.py b/mjlab/src/mjlab/actuator/delayed_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..fa1ac5361787a67b0ac4a17b7baa5f8e7a6edb5f --- /dev/null +++ b/mjlab/src/mjlab/actuator/delayed_actuator.py @@ -0,0 +1,174 @@ +"""Generic delayed actuator wrapper.""" + +from __future__ import annotations + +from dataclasses import dataclass, field +from typing import TYPE_CHECKING, Literal + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.actuator.actuator import Actuator, ActuatorCfg, ActuatorCmd +from mjlab.utils.buffers import DelayBuffer + +if TYPE_CHECKING: + from mjlab.entity import Entity + + +@dataclass(kw_only=True) +class DelayedActuatorCfg(ActuatorCfg): + """Configuration for delayed actuator wrapper. + + Wraps any actuator config to add delay functionality. Delays are quantized + to physics timesteps (not control timesteps). For example, with 500Hz physics + and 50Hz control (decimation=10), a lag of 2 represents a 4ms delay (2 physics + steps). + """ + + target_names_expr: tuple[str, ...] = field(init=False, default=()) + + base_cfg: ActuatorCfg + """Configuration for the underlying actuator.""" + + def __post_init__(self): + object.__setattr__(self, "target_names_expr", self.base_cfg.target_names_expr) + object.__setattr__(self, "transmission_type", self.base_cfg.transmission_type) + + delay_target: ( + Literal["position", "velocity", "effort"] + | tuple[Literal["position", "velocity", "effort"], ...] + ) = "position" + """Which command target(s) to delay. + + Can be a single string like 'position', or a tuple of strings like + ('position', 'velocity', 'effort') to delay multiple targets together. + """ + + delay_min_lag: int = 0 + """Minimum delay lag in physics timesteps.""" + + delay_max_lag: int = 0 + """Maximum delay lag in physics timesteps.""" + + delay_hold_prob: float = 0.0 + """Probability of keeping previous lag when updating.""" + + delay_update_period: int = 0 + """Period for updating delays in physics timesteps (0 = every step).""" + + delay_per_env_phase: bool = True + """Whether each environment has a different phase offset.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> DelayedActuator: + base_actuator = self.base_cfg.build(entity, target_ids, target_names) + return DelayedActuator(self, base_actuator) + + +class DelayedActuator(Actuator[DelayedActuatorCfg]): + """Generic wrapper that adds delay to any actuator. + + Delays the specified command target(s) (position, velocity, and/or effort) + before passing it to the underlying actuator's compute method. + """ + + def __init__(self, cfg: DelayedActuatorCfg, base_actuator: Actuator) -> None: + super().__init__( + cfg, + base_actuator.entity, + base_actuator._target_ids_list, + base_actuator._target_names, + ) + self._base_actuator = base_actuator + self._delay_buffers: dict[str, DelayBuffer] = {} + + @property + def base_actuator(self) -> Actuator: + """The underlying actuator being wrapped.""" + return self._base_actuator + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + self._base_actuator.edit_spec(spec, target_names) + self._mjs_actuators = self._base_actuator._mjs_actuators + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + self._base_actuator.initialize(mj_model, model, data, device) + + self._target_ids = self._base_actuator._target_ids + self._ctrl_ids = self._base_actuator._ctrl_ids + self._global_ctrl_ids = self._base_actuator._global_ctrl_ids + + targets = ( + (self.cfg.delay_target,) + if isinstance(self.cfg.delay_target, str) + else self.cfg.delay_target + ) + + # Create independent delay buffer for each target. + for target in targets: + self._delay_buffers[target] = DelayBuffer( + min_lag=self.cfg.delay_min_lag, + max_lag=self.cfg.delay_max_lag, + batch_size=data.nworld, + device=device, + hold_prob=self.cfg.delay_hold_prob, + update_period=self.cfg.delay_update_period, + per_env_phase=self.cfg.delay_per_env_phase, + ) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + position_target = cmd.position_target + velocity_target = cmd.velocity_target + effort_target = cmd.effort_target + + if "position" in self._delay_buffers: + self._delay_buffers["position"].append(cmd.position_target) + position_target = self._delay_buffers["position"].compute() + + if "velocity" in self._delay_buffers: + self._delay_buffers["velocity"].append(cmd.velocity_target) + velocity_target = self._delay_buffers["velocity"].compute() + + if "effort" in self._delay_buffers: + self._delay_buffers["effort"].append(cmd.effort_target) + effort_target = self._delay_buffers["effort"].compute() + + delayed_cmd = ActuatorCmd( + position_target=position_target, + velocity_target=velocity_target, + effort_target=effort_target, + pos=cmd.pos, + vel=cmd.vel, + ) + + return self._base_actuator.compute(delayed_cmd) + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + for buffer in self._delay_buffers.values(): + buffer.reset(env_ids) + self._base_actuator.reset(env_ids) + + def set_lags( + self, + lags: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set delay lag values for specified environments. + + Args: + lags: Lag values in physics timesteps. Shape: (num_env_ids,) or scalar. + env_ids: Environment indices to set. If None, sets all environments. + """ + for buffer in self._delay_buffers.values(): + buffer.set_lags(lags, env_ids) + + def update(self, dt: float) -> None: + self._base_actuator.update(dt) diff --git a/mjlab/src/mjlab/actuator/learned_actuator.py b/mjlab/src/mjlab/actuator/learned_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..4c124a2aa1689aed0b58461a03ee00654ab9e681 --- /dev/null +++ b/mjlab/src/mjlab/actuator/learned_actuator.py @@ -0,0 +1,207 @@ +"""Learned actuator models.""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Literal + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.actuator.actuator import ActuatorCmd +from mjlab.actuator.dc_actuator import DcMotorActuator, DcMotorActuatorCfg +from mjlab.utils.buffers import CircularBuffer + +if TYPE_CHECKING: + from mjlab.entity import Entity + + +@dataclass(kw_only=True) +class LearnedMlpActuatorCfg(DcMotorActuatorCfg): + """Configuration for MLP-based learned actuator model. + + This actuator learns the mapping from joint commands and state history to + actual torque output. It's useful for capturing actuator dynamics that are + difficult to model analytically, such as delays, non-linearities, and + friction effects. + + The network is trained offline using data from the real system and loaded + as a TorchScript file. The model uses a sliding window of historical joint + position errors and velocities as inputs. + """ + + network_file: str + """Path to the TorchScript file containing the trained MLP model.""" + + pos_scale: float + """Scaling factor for joint position error inputs to the network.""" + + vel_scale: float + """Scaling factor for joint velocity inputs to the network.""" + + torque_scale: float + """Scaling factor for torque outputs from the network.""" + + input_order: Literal["pos_vel", "vel_pos"] = "pos_vel" + """Order of inputs to the network. + + - "pos_vel": position errors followed by velocities + - "vel_pos": velocities followed by position errors + """ + + history_length: int = 3 + """Number of timesteps of history to use as network inputs. + + For example, history_length=3 uses the current timestep plus the previous + 2 timesteps (total of 3 frames). + """ + + # Learned actuators don't use stiffness/damping from PD controller. + stiffness: float = 0.0 + damping: float = 0.0 + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> LearnedMlpActuator: + return LearnedMlpActuator(self, entity, target_ids, target_names) + + +class LearnedMlpActuator(DcMotorActuator[LearnedMlpActuatorCfg]): + """MLP-based learned actuator with joint history. + + This actuator uses a trained neural network to map from joint commands and + state history to torque outputs. The network captures complex actuator + dynamics that are difficult to model analytically. + + The actuator maintains circular buffers of joint position errors and + velocities, which are used as inputs to the MLP. The network outputs are + then scaled and clipped using the DC motor limits from the parent class. + """ + + def __init__( + self, + cfg: LearnedMlpActuatorCfg, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + self.network: torch.jit.ScriptModule | None = None + self._pos_error_history: CircularBuffer | None = None + self._vel_history: CircularBuffer | None = None + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + super().initialize(mj_model, model, data, device) + + # Load the trained network from TorchScript file. + self.network = torch.jit.load(self.cfg.network_file, map_location=device) + assert self.network is not None + self.network.eval() + + # Create history buffers. + num_envs = data.nworld + + self._pos_error_history = CircularBuffer( + max_len=self.cfg.history_length, + batch_size=num_envs, + device=device, + ) + self._vel_history = CircularBuffer( + max_len=self.cfg.history_length, + batch_size=num_envs, + device=device, + ) + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + """Reset history buffers for specified environments. + + Args: + env_ids: Environment indices to reset. If None, reset all environments. + """ + assert self._pos_error_history is not None + assert self._vel_history is not None + + if env_ids is None: + self._pos_error_history.reset() + self._vel_history.reset() + elif isinstance(env_ids, slice): + # Convert slice to indices for CircularBuffer. + batch_size = self._pos_error_history.batch_size + indices = list(range(*env_ids.indices(batch_size))) + self._pos_error_history.reset(indices) + self._vel_history.reset(indices) + else: + self._pos_error_history.reset(env_ids) + self._vel_history.reset(env_ids) + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + """Compute actuator torques using the learned MLP model. + + Args: + cmd: High-level actuator command containing targets and current state. + + Returns: + Computed torque tensor of shape (num_envs, num_joints). + """ + assert self.network is not None + assert self._pos_error_history is not None + assert self._vel_history is not None + assert self._joint_vel_clipped is not None + + # Update history buffers with current state. + pos_error = cmd.position_target - cmd.pos + self._pos_error_history.append(pos_error) + self._vel_history.append(cmd.vel) + + # Save velocity for DC motor clipping in parent class. + self._joint_vel_clipped[:] = cmd.vel + + num_envs = cmd.pos.shape[0] + num_joints = cmd.pos.shape[1] + + # Extract history from current to history_length-1 steps back. + # Each returns shape: (num_envs, num_joints). + pos_inputs = [ + self._pos_error_history[lag] for lag in range(self.cfg.history_length) + ] + vel_inputs = [self._vel_history[lag] for lag in range(self.cfg.history_length)] + + # Stack along feature dimension: (num_envs, num_joints, history_length). + pos_stacked = torch.stack(pos_inputs, dim=2) + vel_stacked = torch.stack(vel_inputs, dim=2) + + # Reshape to (num_envs * num_joints, num_history_steps) for network. + pos_flat = pos_stacked.reshape(num_envs * num_joints, -1) + vel_flat = vel_stacked.reshape(num_envs * num_joints, -1) + + # Scale and concatenate inputs based on specified order. + if self.cfg.input_order == "pos_vel": + network_input = torch.cat( + [pos_flat * self.cfg.pos_scale, vel_flat * self.cfg.vel_scale], dim=1 + ) + elif self.cfg.input_order == "vel_pos": + network_input = torch.cat( + [vel_flat * self.cfg.vel_scale, pos_flat * self.cfg.pos_scale], dim=1 + ) + else: + raise ValueError( + f"Invalid input order: {self.cfg.input_order}. Must be 'pos_vel' or 'vel_pos'." + ) + + # Run network inference. + with torch.inference_mode(): + torques_flat = self.network(network_input) + + # Reshape and scale output torques. + computed_torques = torques_flat.reshape(num_envs, num_joints) + computed_torques = computed_torques * self.cfg.torque_scale + + # Clip using DC motor limits from parent class. + return self._clip_effort(computed_torques) diff --git a/mjlab/src/mjlab/actuator/pd_actuator.py b/mjlab/src/mjlab/actuator/pd_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..f33ec4b1081ef4f152bbe2afa60725d29a4dfeb2 --- /dev/null +++ b/mjlab/src/mjlab/actuator/pd_actuator.py @@ -0,0 +1,150 @@ +"""An ideal PD control actuator.""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Generic, TypeVar + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.actuator.actuator import Actuator, ActuatorCfg, ActuatorCmd +from mjlab.utils.spec import create_motor_actuator + +if TYPE_CHECKING: + from mjlab.entity import Entity + +IdealPdCfgT = TypeVar("IdealPdCfgT", bound="IdealPdActuatorCfg") + + +@dataclass(kw_only=True) +class IdealPdActuatorCfg(ActuatorCfg): + """Configuration for ideal PD actuator.""" + + stiffness: float + """PD stiffness (proportional gain).""" + damping: float + """PD damping (derivative gain).""" + effort_limit: float = float("inf") + """Maximum force/torque limit.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> IdealPdActuator: + return IdealPdActuator(self, entity, target_ids, target_names) + + +class IdealPdActuator(Actuator, Generic[IdealPdCfgT]): + """Ideal PD control actuator.""" + + def __init__( + self, + cfg: IdealPdCfgT, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + self.stiffness: torch.Tensor | None = None + self.damping: torch.Tensor | None = None + self.force_limit: torch.Tensor | None = None + self.default_stiffness: torch.Tensor | None = None + self.default_damping: torch.Tensor | None = None + self.default_force_limit: torch.Tensor | None = None + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Add actuator to spec, one per target. + for target_name in target_names: + actuator = create_motor_actuator( + spec, + target_name, + effort_limit=self.cfg.effort_limit, + armature=self.cfg.armature, + frictionloss=self.cfg.frictionloss, + transmission_type=self.cfg.transmission_type, + ) + self._mjs_actuators.append(actuator) + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + super().initialize(mj_model, model, data, device) + + num_envs = data.nworld + num_joints = len(self._target_names) + self.stiffness = torch.full( + (num_envs, num_joints), self.cfg.stiffness, dtype=torch.float, device=device + ) + self.damping = torch.full( + (num_envs, num_joints), self.cfg.damping, dtype=torch.float, device=device + ) + self.force_limit = torch.full( + (num_envs, num_joints), self.cfg.effort_limit, dtype=torch.float, device=device + ) + + self.default_stiffness = self.stiffness.clone() + self.default_damping = self.damping.clone() + self.default_force_limit = self.force_limit.clone() + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + assert self.stiffness is not None + assert self.damping is not None + + pos_error = cmd.position_target - cmd.pos + vel_error = cmd.velocity_target - cmd.vel + + computed_torques = self.stiffness * pos_error + computed_torques += self.damping * vel_error + computed_torques += cmd.effort_target + + return self._clip_effort(computed_torques) + + def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor: + assert self.force_limit is not None + return torch.clamp(effort, -self.force_limit, self.force_limit) + + def set_gains( + self, + env_ids: torch.Tensor | slice, + kp: torch.Tensor | None = None, + kd: torch.Tensor | None = None, + ) -> None: + """Set PD gains for specified environments. + + Args: + env_ids: Environment indices to update. + kp: New proportional gains. Shape: (num_envs, num_actuators) or (num_envs,). + kd: New derivative gains. Shape: (num_envs, num_actuators) or (num_envs,). + """ + assert self.stiffness is not None + assert self.damping is not None + + if kp is not None: + if kp.ndim == 1: + kp = kp.unsqueeze(-1) + self.stiffness[env_ids] = kp + + if kd is not None: + if kd.ndim == 1: + kd = kd.unsqueeze(-1) + self.damping[env_ids] = kd + + def set_effort_limit( + self, env_ids: torch.Tensor | slice, effort_limit: torch.Tensor + ) -> None: + """Set effort limits for specified environments. + + Args: + env_ids: Environment indices to update. + effort_limit: New effort limits. Shape: (num_envs, num_actuators) or (num_envs,). + """ + assert self.force_limit is not None + + if effort_limit.ndim == 1: + effort_limit = effort_limit.unsqueeze(-1) + self.force_limit[env_ids] = effort_limit diff --git a/mjlab/src/mjlab/actuator/xml_actuator.py b/mjlab/src/mjlab/actuator/xml_actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..64301ea8c74bb3e1f73401f4a9972d5c824980f3 --- /dev/null +++ b/mjlab/src/mjlab/actuator/xml_actuator.py @@ -0,0 +1,131 @@ +"""Wrappers for XML-defined actuators. + +This module provides wrappers for actuators already defined in robot XML/MJCF files. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Generic, TypeVar + +import mujoco +import torch + +from mjlab.actuator.actuator import Actuator, ActuatorCfg, ActuatorCmd + +if TYPE_CHECKING: + from mjlab.entity import Entity + +XmlActuatorCfgT = TypeVar("XmlActuatorCfgT", bound=ActuatorCfg) + + +class XmlActuator(Actuator[XmlActuatorCfgT], Generic[XmlActuatorCfgT]): + """Base class for XML-defined actuators.""" + + def __init__( + self, + cfg: XmlActuatorCfgT, + entity: Entity, + target_ids: list[int], + target_names: list[str], + ) -> None: + super().__init__(cfg, entity, target_ids, target_names) + + def edit_spec(self, spec: mujoco.MjSpec, target_names: list[str]) -> None: + # Filter to only targets that have corresponding XML actuators. + filtered_target_ids = [] + filtered_target_names = [] + for i, target_name in enumerate(target_names): + actuator = self._find_actuator_for_target(spec, target_name) + if actuator is not None: + self._mjs_actuators.append(actuator) + filtered_target_ids.append(self._target_ids_list[i]) + filtered_target_names.append(target_name) + + if len(filtered_target_names) == 0: + raise ValueError( + f"No XML actuators found for any targets matching the patterns. " + f"Searched targets: {target_names}. " + f"XML actuator config expects actuators to already exist in the XML." + ) + + # Update target IDs and names to only include those with actuators. + self._target_ids_list = filtered_target_ids + self._target_names = filtered_target_names + + def _find_actuator_for_target( + self, spec: mujoco.MjSpec, target_name: str + ) -> mujoco.MjsActuator | None: + """Find an actuator that targets the given target (joint, tendon, or site).""" + for actuator in spec.actuators: + if actuator.target == target_name: + return actuator + return None + + +@dataclass(kw_only=True) +class XmlPositionActuatorCfg(ActuatorCfg): + """Wrap existing XML-defined actuators.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> XmlPositionActuator: + return XmlPositionActuator(self, entity, target_ids, target_names) + + +class XmlPositionActuator(XmlActuator[XmlPositionActuatorCfg]): + """Wrapper for XML-defined actuators.""" + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.position_target + + +@dataclass(kw_only=True) +class XmlMotorActuatorCfg(ActuatorCfg): + """Wrap existing XML-defined actuators.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> XmlMotorActuator: + return XmlMotorActuator(self, entity, target_ids, target_names) + + +class XmlMotorActuator(XmlActuator[XmlMotorActuatorCfg]): + """Wrapper for XML-defined actuators.""" + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.effort_target + + +@dataclass(kw_only=True) +class XmlVelocityActuatorCfg(ActuatorCfg): + """Wrap existing XML-defined actuators.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> XmlVelocityActuator: + return XmlVelocityActuator(self, entity, target_ids, target_names) + + +class XmlVelocityActuator(XmlActuator[XmlVelocityActuatorCfg]): + """Wrapper for XML-defined actuators.""" + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.velocity_target + + +@dataclass(kw_only=True) +class XmlMuscleActuatorCfg(ActuatorCfg): + """Wrap existing XML-defined actuators.""" + + def build( + self, entity: Entity, target_ids: list[int], target_names: list[str] + ) -> XmlMuscleActuator: + return XmlMuscleActuator(self, entity, target_ids, target_names) + + +class XmlMuscleActuator(XmlActuator[XmlMuscleActuatorCfg]): + """Wrapper for XML-defined actuators.""" + + def compute(self, cmd: ActuatorCmd) -> torch.Tensor: + return cmd.effort_target diff --git a/mjlab/src/mjlab/asset_zoo/README.md b/mjlab/src/mjlab/asset_zoo/README.md new file mode 100644 index 0000000000000000000000000000000000000000..24663cff281de97cf5cb8853b8a5b9d2de8b48eb --- /dev/null +++ b/mjlab/src/mjlab/asset_zoo/README.md @@ -0,0 +1,7 @@ +# Asset Zoo + +| Robot | Image | +|-------|-------| +| **Unitree G1** | Unitree G1 Humanoid | +| **Unitree Go1** | Unitree Go1 Quadruped | +| **i2rt YAM** | i2rt YAM Robot Arm | diff --git a/mjlab/src/mjlab/asset_zoo/__init__.py b/mjlab/src/mjlab/asset_zoo/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/mjlab/src/mjlab/entity/__init__.py b/mjlab/src/mjlab/entity/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..935e2bf6c7ec1f5aea75d4f73ea5ec38cf3e5f5a --- /dev/null +++ b/mjlab/src/mjlab/entity/__init__.py @@ -0,0 +1,5 @@ +from mjlab.entity.data import EntityData as EntityData +from mjlab.entity.entity import Entity as Entity +from mjlab.entity.entity import EntityArticulationInfoCfg as EntityArticulationInfoCfg +from mjlab.entity.entity import EntityCfg as EntityCfg +from mjlab.entity.entity import EntityIndexing as EntityIndexing diff --git a/mjlab/src/mjlab/entity/data.py b/mjlab/src/mjlab/entity/data.py new file mode 100644 index 0000000000000000000000000000000000000000..80bef750bd4a43a02fba64d6dac04b0e06da4603 --- /dev/null +++ b/mjlab/src/mjlab/entity/data.py @@ -0,0 +1,576 @@ +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Sequence + +import mujoco_warp as mjwarp +import torch + +from mjlab.utils.lab_api.math import ( + quat_apply, + quat_apply_inverse, + quat_from_matrix, + quat_mul, +) + +if TYPE_CHECKING: + from mjlab.entity.entity import EntityIndexing + + +def compute_velocity_from_cvel( + pos: torch.Tensor, + subtree_com: torch.Tensor, + cvel: torch.Tensor, +) -> torch.Tensor: + """Convert cvel quantities to world-frame velocities.""" + lin_vel_c = cvel[..., 3:6] + ang_vel_c = cvel[..., 0:3] + offset = subtree_com - pos + lin_vel_w = lin_vel_c - torch.cross(ang_vel_c, offset, dim=-1) + ang_vel_w = ang_vel_c + return torch.cat([lin_vel_w, ang_vel_w], dim=-1) + + +@dataclass +class EntityData: + """Data container for an entity. + + Note: Write methods (write_*) modify state directly. Read properties (e.g., + root_link_pose_w) require sim.forward() to be current. If you write then read, + call sim.forward() in between. Event order matters when mixing reads and writes. + All inputs/outputs use world frame. + """ + + indexing: EntityIndexing + data: mjwarp.Data + model: mjwarp.Model + device: str + + default_root_state: torch.Tensor + default_joint_pos: torch.Tensor + default_joint_vel: torch.Tensor + + default_joint_pos_limits: torch.Tensor + joint_pos_limits: torch.Tensor + soft_joint_pos_limits: torch.Tensor + + gravity_vec_w: torch.Tensor + forward_vec_b: torch.Tensor + + is_fixed_base: bool + is_articulated: bool + is_actuated: bool + + joint_pos_target: torch.Tensor + joint_vel_target: torch.Tensor + joint_effort_target: torch.Tensor + + tendon_len_target: torch.Tensor + tendon_vel_target: torch.Tensor + tendon_effort_target: torch.Tensor + + site_effort_target: torch.Tensor + + encoder_bias: torch.Tensor + + # State dimensions. + POS_DIM = 3 + QUAT_DIM = 4 + LIN_VEL_DIM = 3 + ANG_VEL_DIM = 3 + ROOT_POSE_DIM = POS_DIM + QUAT_DIM # 7 + ROOT_VEL_DIM = LIN_VEL_DIM + ANG_VEL_DIM # 6 + ROOT_STATE_DIM = ROOT_POSE_DIM + ROOT_VEL_DIM # 13 + + def write_root_state( + self, root_state: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + if self.is_fixed_base: + raise ValueError("Cannot write root state for fixed-base entity.") + assert root_state.shape[-1] == self.ROOT_STATE_DIM + + self.write_root_pose(root_state[:, : self.ROOT_POSE_DIM], env_ids) + self.write_root_velocity(root_state[:, self.ROOT_POSE_DIM :], env_ids) + + def write_root_pose( + self, pose: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + if self.is_fixed_base: + raise ValueError("Cannot write root pose for fixed-base entity.") + assert pose.shape[-1] == self.ROOT_POSE_DIM + + env_ids = self._resolve_env_ids(env_ids) + self.data.qpos[env_ids, self.indexing.free_joint_q_adr] = pose + + def write_root_velocity( + self, velocity: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + if self.is_fixed_base: + raise ValueError("Cannot write root velocity for fixed-base entity.") + assert velocity.shape[-1] == self.ROOT_VEL_DIM + + env_ids = self._resolve_env_ids(env_ids) + quat_w = self.data.qpos[env_ids, self.indexing.free_joint_q_adr[3:7]] + ang_vel_b = quat_apply_inverse(quat_w, velocity[:, 3:]) + velocity_qvel = torch.cat([velocity[:, :3], ang_vel_b], dim=-1) + self.data.qvel[env_ids, self.indexing.free_joint_v_adr] = velocity_qvel + + def write_root_com_velocity( + self, velocity: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + if self.is_fixed_base: + raise ValueError("Cannot write root COM velocity for fixed-base entity.") + assert velocity.shape[-1] == self.ROOT_VEL_DIM + + env_ids = self._resolve_env_ids(env_ids) + com_offset_b = self.model.body_ipos[:, self.indexing.root_body_id] + quat_w = self.data.qpos[env_ids, self.indexing.free_joint_q_adr[3:7]] + com_offset_w = quat_apply(quat_w, com_offset_b[env_ids]) + lin_vel_com = velocity[:, :3] + ang_vel_w = velocity[:, 3:] + lin_vel_link = lin_vel_com - torch.cross(ang_vel_w, com_offset_w, dim=-1) + link_velocity = torch.cat([lin_vel_link, ang_vel_w], dim=-1) + self.write_root_velocity(link_velocity, env_ids) + + def write_joint_state( + self, + position: torch.Tensor, + velocity: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + if not self.is_articulated: + raise ValueError("Cannot write joint state for non-articulated entity.") + + self.write_joint_position(position, joint_ids, env_ids) + self.write_joint_velocity(velocity, joint_ids, env_ids) + + def write_joint_position( + self, + position: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + if not self.is_articulated: + raise ValueError("Cannot write joint position for non-articulated entity.") + + env_ids = self._resolve_env_ids(env_ids) + joint_ids = joint_ids if joint_ids is not None else slice(None) + q_slice = self.indexing.joint_q_adr[joint_ids] + self.data.qpos[env_ids, q_slice] = position + + def write_joint_velocity( + self, + velocity: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + if not self.is_articulated: + raise ValueError("Cannot write joint velocity for non-articulated entity.") + + env_ids = self._resolve_env_ids(env_ids) + joint_ids = joint_ids if joint_ids is not None else slice(None) + v_slice = self.indexing.joint_v_adr[joint_ids] + self.data.qvel[env_ids, v_slice] = velocity + + def write_external_wrench( + self, + force: torch.Tensor | None, + torque: torch.Tensor | None, + body_ids: Sequence[int] | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + env_ids = self._resolve_env_ids(env_ids) + local_body_ids = body_ids if body_ids is not None else slice(None) + global_body_ids = self.indexing.body_ids[local_body_ids] + if force is not None: + self.data.xfrc_applied[env_ids, global_body_ids, 0:3] = force + if torque is not None: + self.data.xfrc_applied[env_ids, global_body_ids, 3:6] = torque + + def write_ctrl( + self, + ctrl: torch.Tensor, + ctrl_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + if not self.is_actuated: + raise ValueError("Cannot write control for non-actuated entity.") + + env_ids = self._resolve_env_ids(env_ids) + local_ctrl_ids = ctrl_ids if ctrl_ids is not None else slice(None) + global_ctrl_ids = self.indexing.ctrl_ids[local_ctrl_ids] + self.data.ctrl[env_ids, global_ctrl_ids] = ctrl + + def write_mocap_pose( + self, pose: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + if self.indexing.mocap_id is None: + raise ValueError("Cannot write mocap pose for non-mocap entity.") + assert pose.shape[-1] == self.ROOT_POSE_DIM + + env_ids = self._resolve_env_ids(env_ids) + self.data.mocap_pos[env_ids, self.indexing.mocap_id] = pose[:, 0:3].unsqueeze(1) + self.data.mocap_quat[env_ids, self.indexing.mocap_id] = pose[:, 3:7].unsqueeze(1) + + def clear_state(self, env_ids: torch.Tensor | slice | None = None) -> None: + if self.is_actuated: + env_ids = self._resolve_env_ids(env_ids) + self.joint_pos_target[env_ids] = 0.0 + self.joint_vel_target[env_ids] = 0.0 + self.joint_effort_target[env_ids] = 0.0 + self.tendon_len_target[env_ids] = 0.0 + self.tendon_vel_target[env_ids] = 0.0 + self.tendon_effort_target[env_ids] = 0.0 + self.site_effort_target[env_ids] = 0.0 + + def _resolve_env_ids( + self, env_ids: torch.Tensor | slice | None + ) -> torch.Tensor | slice: + """Convert env_ids to consistent indexing format.""" + if env_ids is None: + return slice(None) + if isinstance(env_ids, torch.Tensor): + return env_ids[:, None] + return env_ids + + # Root properties + + @property + def root_link_pose_w(self) -> torch.Tensor: + """Root link pose in world frame. Shape (num_envs, 7).""" + pos_w = self.data.xpos[:, self.indexing.root_body_id] # (num_envs, 3) + quat_w = self.data.xquat[:, self.indexing.root_body_id] # (num_envs, 4) + return torch.cat([pos_w, quat_w], dim=-1) # (num_envs, 7) + + @property + def root_link_vel_w(self) -> torch.Tensor: + """Root link velocity in world frame. Shape (num_envs, 6).""" + # NOTE: Equivalently, can read this from qvel[:6] but the angular part + # will be in body frame and needs to be rotated to world frame. + # Note also that an extra forward() call might be required to make + # both values equal. + pos = self.data.xpos[:, self.indexing.root_body_id] # (num_envs, 3) + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, self.indexing.root_body_id] # (num_envs, 6) + return compute_velocity_from_cvel(pos, subtree_com, cvel) # (num_envs, 6) + + @property + def root_com_pose_w(self) -> torch.Tensor: + """Root center-of-mass pose in world frame. Shape (num_envs, 7).""" + pos_w = self.data.xipos[:, self.indexing.root_body_id] + quat = self.data.xquat[:, self.indexing.root_body_id] + body_iquat = self.model.body_iquat[:, self.indexing.root_body_id] + assert body_iquat is not None + quat_w = quat_mul(quat, body_iquat.squeeze(1)) + return torch.cat([pos_w, quat_w], dim=-1) + + @property + def root_com_vel_w(self) -> torch.Tensor: + """Root center-of-mass velocity in world frame. Shape (num_envs, 6).""" + # NOTE: Equivalent sensor is framelinvel/frameangvel with objtype="body". + pos = self.data.xipos[:, self.indexing.root_body_id] # (num_envs, 3) + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, self.indexing.root_body_id] # (num_envs, 6) + return compute_velocity_from_cvel(pos, subtree_com, cvel) # (num_envs, 6) + + # Body properties + + @property + def body_link_pose_w(self) -> torch.Tensor: + """Body link pose in world frame. Shape (num_envs, num_bodies, 7).""" + pos_w = self.data.xpos[:, self.indexing.body_ids] + quat_w = self.data.xquat[:, self.indexing.body_ids] + return torch.cat([pos_w, quat_w], dim=-1) + + @property + def body_link_vel_w(self) -> torch.Tensor: + """Body link velocity in world frame. Shape (num_envs, num_bodies, 6).""" + # NOTE: Equivalent sensor is framelinvel/frameangvel with objtype="xbody". + pos = self.data.xpos[:, self.indexing.body_ids] # (num_envs, num_bodies, 3) + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, self.indexing.body_ids] + return compute_velocity_from_cvel(pos, subtree_com.unsqueeze(1), cvel) + + @property + def body_com_pose_w(self) -> torch.Tensor: + """Body center-of-mass pose in world frame. Shape (num_envs, num_bodies, 7).""" + pos_w = self.data.xipos[:, self.indexing.body_ids] + quat = self.data.xquat[:, self.indexing.body_ids] + body_iquat = self.model.body_iquat[:, self.indexing.body_ids] + quat_w = quat_mul(quat, body_iquat) + return torch.cat([pos_w, quat_w], dim=-1) + + @property + def body_com_vel_w(self) -> torch.Tensor: + """Body center-of-mass velocity in world frame. Shape (num_envs, num_bodies, 6).""" + # NOTE: Equivalent sensor is framelinvel/frameangvel with objtype="body". + pos = self.data.xipos[:, self.indexing.body_ids] + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, self.indexing.body_ids] + return compute_velocity_from_cvel(pos, subtree_com.unsqueeze(1), cvel) + + @property + def body_external_wrench(self) -> torch.Tensor: + """Body external wrench in world frame. Shape (num_envs, num_bodies, 6).""" + return self.data.xfrc_applied[:, self.indexing.body_ids] + + # Geom properties + + @property + def geom_pose_w(self) -> torch.Tensor: + """Geom pose in world frame. Shape (num_envs, num_geoms, 7).""" + pos_w = self.data.geom_xpos[:, self.indexing.geom_ids] + xmat = self.data.geom_xmat[:, self.indexing.geom_ids] + quat_w = quat_from_matrix(xmat) + return torch.cat([pos_w, quat_w], dim=-1) + + @property + def geom_vel_w(self) -> torch.Tensor: + """Geom velocity in world frame. Shape (num_envs, num_geoms, 6).""" + pos = self.data.geom_xpos[:, self.indexing.geom_ids] + body_ids = self.model.geom_bodyid[self.indexing.geom_ids] # (num_geoms,) + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, body_ids] + return compute_velocity_from_cvel(pos, subtree_com.unsqueeze(1), cvel) + + # Site properties + + @property + def site_pose_w(self) -> torch.Tensor: + """Site pose in world frame. Shape (num_envs, num_sites, 7).""" + pos_w = self.data.site_xpos[:, self.indexing.site_ids] + mat_w = self.data.site_xmat[:, self.indexing.site_ids] + quat_w = quat_from_matrix(mat_w) + return torch.cat([pos_w, quat_w], dim=-1) + + @property + def site_vel_w(self) -> torch.Tensor: + """Site velocity in world frame. Shape (num_envs, num_sites, 6).""" + pos = self.data.site_xpos[:, self.indexing.site_ids] + body_ids = self.model.site_bodyid[self.indexing.site_ids] # (num_sites,) + subtree_com = self.data.subtree_com[:, self.indexing.root_body_id] + cvel = self.data.cvel[:, body_ids] + return compute_velocity_from_cvel(pos, subtree_com.unsqueeze(1), cvel) + + # Joint properties + + @property + def joint_pos(self) -> torch.Tensor: + """Joint positions. Shape (num_envs, num_joints).""" + return self.data.qpos[:, self.indexing.joint_q_adr] + + @property + def joint_pos_biased(self) -> torch.Tensor: + """Joint positions with encoder bias applied. Shape (num_envs, num_joints).""" + return self.joint_pos + self.encoder_bias + + @property + def joint_vel(self) -> torch.Tensor: + """Joint velocities. Shape (num_envs, nv).""" + return self.data.qvel[:, self.indexing.joint_v_adr] + + @property + def joint_acc(self) -> torch.Tensor: + """Joint accelerations. Shape (num_envs, nv).""" + return self.data.qacc[:, self.indexing.joint_v_adr] + + # Tendon properties + + @property + def tendon_len(self) -> torch.Tensor: + """Tendon lengths. Shape (num_envs, num_tendons).""" + return self.data.ten_length[:, self.indexing.tendon_ids] + + @property + def tendon_vel(self) -> torch.Tensor: + """Tendon velocities. Shape (num_envs, num_tendons).""" + return self.data.ten_velocity[:, self.indexing.tendon_ids] + + @property + def joint_torques(self) -> torch.Tensor: + """Joint torques. Shape (num_envs, nv).""" + raise NotImplementedError( + "Joint torques are not currently available. " + "Consider using 'actuator_force' property for actuation forces, " + "or 'generalized_force' property for generalized forces applied to the DoFs." + ) + + @property + def actuator_force(self) -> torch.Tensor: + """Scalar actuation force in actuation space. Shape (num_envs, nu).""" + return self.data.actuator_force[:, self.indexing.ctrl_ids] + + @property + def generalized_force(self) -> torch.Tensor: + """Generalized forces applied to the DoFs. Shape (num_envs, nv).""" + return self.data.qfrc_applied[:, self.indexing.free_joint_v_adr] + + # Pose and velocity component accessors. + + @property + def root_link_pos_w(self) -> torch.Tensor: + """Root link position in world frame. Shape (num_envs, 3).""" + return self.root_link_pose_w[:, 0:3] + + @property + def root_link_quat_w(self) -> torch.Tensor: + """Root link quaternion in world frame. Shape (num_envs, 4).""" + return self.root_link_pose_w[:, 3:7] + + @property + def root_link_lin_vel_w(self) -> torch.Tensor: + """Root link linear velocity in world frame. Shape (num_envs, 3).""" + return self.root_link_vel_w[:, 0:3] + + @property + def root_link_ang_vel_w(self) -> torch.Tensor: + """Root link angular velocity in world frame. Shape (num_envs, 3).""" + return self.data.cvel[:, self.indexing.root_body_id, 0:3] + + @property + def root_com_pos_w(self) -> torch.Tensor: + """Root COM position in world frame. Shape (num_envs, 3).""" + return self.root_com_pose_w[:, 0:3] + + @property + def root_com_quat_w(self) -> torch.Tensor: + """Root COM quaternion in world frame. Shape (num_envs, 4).""" + return self.root_com_pose_w[:, 3:7] + + @property + def root_com_lin_vel_w(self) -> torch.Tensor: + """Root COM linear velocity in world frame. Shape (num_envs, 3).""" + return self.root_com_vel_w[:, 0:3] + + @property + def root_com_ang_vel_w(self) -> torch.Tensor: + """Root COM angular velocity in world frame. Shape (num_envs, 3).""" + # Angular velocity is the same for link and COM frames. + return self.data.cvel[:, self.indexing.root_body_id, 0:3] + + @property + def body_link_pos_w(self) -> torch.Tensor: + """Body link positions in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_link_pose_w[..., 0:3] + + @property + def body_link_quat_w(self) -> torch.Tensor: + """Body link quaternions in world frame. Shape (num_envs, num_bodies, 4).""" + return self.body_link_pose_w[..., 3:7] + + @property + def body_link_lin_vel_w(self) -> torch.Tensor: + """Body link linear velocities in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_link_vel_w[..., 0:3] + + @property + def body_link_ang_vel_w(self) -> torch.Tensor: + """Body link angular velocities in world frame. Shape (num_envs, num_bodies, 3).""" + return self.data.cvel[:, self.indexing.body_ids, 0:3] + + @property + def body_com_pos_w(self) -> torch.Tensor: + """Body COM positions in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_com_pose_w[..., 0:3] + + @property + def body_com_quat_w(self) -> torch.Tensor: + """Body COM quaternions in world frame. Shape (num_envs, num_bodies, 4).""" + return self.body_com_pose_w[..., 3:7] + + @property + def body_com_lin_vel_w(self) -> torch.Tensor: + """Body COM linear velocities in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_com_vel_w[..., 0:3] + + @property + def body_com_ang_vel_w(self) -> torch.Tensor: + """Body COM angular velocities in world frame. Shape (num_envs, num_bodies, 3).""" + # Angular velocity is the same for link and COM frames. + return self.data.cvel[:, self.indexing.body_ids, 0:3] + + @property + def body_external_force(self) -> torch.Tensor: + """Body external forces in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_external_wrench[..., 0:3] + + @property + def body_external_torque(self) -> torch.Tensor: + """Body external torques in world frame. Shape (num_envs, num_bodies, 3).""" + return self.body_external_wrench[..., 3:6] + + @property + def geom_pos_w(self) -> torch.Tensor: + """Geom positions in world frame. Shape (num_envs, num_geoms, 3).""" + return self.geom_pose_w[..., 0:3] + + @property + def geom_quat_w(self) -> torch.Tensor: + """Geom quaternions in world frame. Shape (num_envs, num_geoms, 4).""" + return self.geom_pose_w[..., 3:7] + + @property + def geom_lin_vel_w(self) -> torch.Tensor: + """Geom linear velocities in world frame. Shape (num_envs, num_geoms, 3).""" + return self.geom_vel_w[..., 0:3] + + @property + def geom_ang_vel_w(self) -> torch.Tensor: + """Geom angular velocities in world frame. Shape (num_envs, num_geoms, 3).""" + body_ids = self.model.geom_bodyid[self.indexing.geom_ids] + return self.data.cvel[:, body_ids, 0:3] + + @property + def site_pos_w(self) -> torch.Tensor: + """Site positions in world frame. Shape (num_envs, num_sites, 3).""" + return self.site_pose_w[..., 0:3] + + @property + def site_quat_w(self) -> torch.Tensor: + """Site quaternions in world frame. Shape (num_envs, num_sites, 4).""" + return self.site_pose_w[..., 3:7] + + @property + def site_lin_vel_w(self) -> torch.Tensor: + """Site linear velocities in world frame. Shape (num_envs, num_sites, 3).""" + return self.site_vel_w[..., 0:3] + + @property + def site_ang_vel_w(self) -> torch.Tensor: + """Site angular velocities in world frame. Shape (num_envs, num_sites, 3).""" + body_ids = self.model.site_bodyid[self.indexing.site_ids] + return self.data.cvel[:, body_ids, 0:3] + + # Derived properties. + + @property + def projected_gravity_b(self) -> torch.Tensor: + """Gravity vector projected into body frame. Shape (num_envs, 3).""" + return quat_apply_inverse(self.root_link_quat_w, self.gravity_vec_w) + + @property + def heading_w(self) -> torch.Tensor: + """Heading angle in world frame. Shape (num_envs,).""" + forward_w = quat_apply(self.root_link_quat_w, self.forward_vec_b) + return torch.atan2(forward_w[:, 1], forward_w[:, 0]) + + @property + def root_link_lin_vel_b(self) -> torch.Tensor: + """Root link linear velocity in body frame. Shape (num_envs, 3).""" + return quat_apply_inverse(self.root_link_quat_w, self.root_link_lin_vel_w) + + @property + def root_link_ang_vel_b(self) -> torch.Tensor: + """Root link angular velocity in body frame. Shape (num_envs, 3).""" + return quat_apply_inverse(self.root_link_quat_w, self.root_link_ang_vel_w) + + @property + def root_com_lin_vel_b(self) -> torch.Tensor: + """Root COM linear velocity in body frame. Shape (num_envs, 3).""" + return quat_apply_inverse(self.root_link_quat_w, self.root_com_lin_vel_w) + + @property + def root_com_ang_vel_b(self) -> torch.Tensor: + """Root COM angular velocity in body frame. Shape (num_envs, 3).""" + return quat_apply_inverse(self.root_link_quat_w, self.root_com_ang_vel_w) diff --git a/mjlab/src/mjlab/entity/entity.py b/mjlab/src/mjlab/entity/entity.py new file mode 100644 index 0000000000000000000000000000000000000000..1466106a7d402a4a0e51cf1fdcbf7cba8321e64c --- /dev/null +++ b/mjlab/src/mjlab/entity/entity.py @@ -0,0 +1,985 @@ +from __future__ import annotations + +from dataclasses import dataclass, field +from pathlib import Path +from typing import Callable, Sequence + +import mujoco +import mujoco_warp as mjwarp +import numpy as np +import torch + +from mjlab import actuator +from mjlab.actuator import BuiltinActuatorGroup +from mjlab.actuator.actuator import TransmissionType +from mjlab.entity.data import EntityData +from mjlab.utils import spec_config as spec_cfg +from mjlab.utils.lab_api.string import resolve_matching_names +from mjlab.utils.mujoco import dof_width, qpos_width +from mjlab.utils.spec import auto_wrap_fixed_base_mocap +from mjlab.utils.string import resolve_expr + + +@dataclass(frozen=False) +class EntityIndexing: + """Maps entity elements to global indices and addresses in the simulation.""" + + # Elements. + bodies: tuple[mujoco.MjsBody, ...] + joints: tuple[mujoco.MjsJoint, ...] + geoms: tuple[mujoco.MjsGeom, ...] + sites: tuple[mujoco.MjsSite, ...] + tendons: tuple[mujoco.MjsTendon, ...] + actuators: tuple[mujoco.MjsActuator, ...] | None + + # Indices. + body_ids: torch.Tensor + geom_ids: torch.Tensor + site_ids: torch.Tensor + tendon_ids: torch.Tensor + ctrl_ids: torch.Tensor + joint_ids: torch.Tensor + mocap_id: int | None + + # Addresses. + joint_q_adr: torch.Tensor + joint_v_adr: torch.Tensor + free_joint_q_adr: torch.Tensor + free_joint_v_adr: torch.Tensor + + @property + def root_body_id(self) -> int: + return self.bodies[0].id + + +@dataclass +class EntityCfg: + @dataclass + class InitialStateCfg: + # Root position and orientation. + pos: tuple[float, float, float] = (0.0, 0.0, 0.0) + rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0) + # Root linear and angular velocity (only for floating base entities). + lin_vel: tuple[float, float, float] = (0.0, 0.0, 0.0) + ang_vel: tuple[float, float, float] = (0.0, 0.0, 0.0) + # Articulation (only for articulated entities). + # Set to None to use the model's existing keyframe (errors if none exists). + joint_pos: dict[str, float] | None = field(default_factory=lambda: {".*": 0.0}) + joint_vel: dict[str, float] = field(default_factory=lambda: {".*": 0.0}) + + init_state: InitialStateCfg = field(default_factory=InitialStateCfg) + spec_fn: Callable[[], mujoco.MjSpec] = field( + default_factory=lambda: (lambda: mujoco.MjSpec()) + ) + articulation: EntityArticulationInfoCfg | None = None + + # Editors. + lights: tuple[spec_cfg.LightCfg, ...] = field(default_factory=tuple) + cameras: tuple[spec_cfg.CameraCfg, ...] = field(default_factory=tuple) + textures: tuple[spec_cfg.TextureCfg, ...] = field(default_factory=tuple) + materials: tuple[spec_cfg.MaterialCfg, ...] = field(default_factory=tuple) + collisions: tuple[spec_cfg.CollisionCfg, ...] = field(default_factory=tuple) + + def build(self) -> Entity: + """Build entity instance from this config. + + Override in subclasses to return custom Entity types. + """ + return Entity(self) + + +@dataclass +class EntityArticulationInfoCfg: + actuators: tuple[actuator.ActuatorCfg, ...] = field(default_factory=tuple) + soft_joint_pos_limit_factor: float = 1.0 + + +class Entity: + """An entity represents a physical object in the simulation. + + Entity Type Matrix + ================== + MuJoCo entities can be categorized along two dimensions: + + 1. Base Type: + - Fixed Base: Entity is welded to the world (no freejoint) + - Floating Base: Entity has 6 DOF movement (has freejoint) + + 2. Articulation: + - Non-articulated: No joints other than freejoint + - Articulated: Has joints in kinematic tree (may or may not be actuated) + + Fixed non-articulated entities can optionally be mocap bodies, whereby their + position and orientation can be set directly each timestep rather than being + determined by physics. This property can be useful for creating props with + adjustable position and orientation. + + Supported Combinations: + ---------------------- + | Type | Example | is_fixed_base | is_articulated | is_actuated | + |---------------------------|---------------------|---------------|----------------|-------------| + | Fixed Non-articulated | Table, wall | True | False | False | + | Fixed Articulated | Robot arm, door | True | True | True/False | + | Floating Non-articulated | Box, ball, mug | False | False | False | + | Floating Articulated | Humanoid, quadruped | False | True | True/False | + """ + + def __init__(self, cfg: EntityCfg) -> None: + self.cfg = cfg + self._spec = auto_wrap_fixed_base_mocap(cfg.spec_fn)() + + # Identify free joint and articulated joints. + self._all_joints = self._spec.joints + self._free_joint = None + self._non_free_joints = tuple(self._all_joints) + if self._all_joints and self._all_joints[0].type == mujoco.mjtJoint.mjJNT_FREE: + self._free_joint = self._all_joints[0] + if not self._free_joint.name: + self._free_joint.name = "floating_base_joint" + self._non_free_joints = tuple(self._all_joints[1:]) + self._actuators: list[actuator.Actuator] = [] + + self._apply_spec_editors() + self._add_actuators() + self._add_initial_state_keyframe() + + def _apply_spec_editors(self) -> None: + for cfg_list in [ + self.cfg.lights, + self.cfg.cameras, + self.cfg.textures, + self.cfg.materials, + self.cfg.collisions, + ]: + for cfg in cfg_list: + cfg.edit_spec(self._spec) + + def _add_actuators(self) -> None: + if self.cfg.articulation is None: + return + + for actuator_cfg in self.cfg.articulation.actuators: + # Find targets based on transmission type. + if actuator_cfg.transmission_type == TransmissionType.JOINT: + target_ids, target_names = self.find_joints(actuator_cfg.target_names_expr) + elif actuator_cfg.transmission_type == TransmissionType.TENDON: + target_ids, target_names = self.find_tendons(actuator_cfg.target_names_expr) + elif actuator_cfg.transmission_type == TransmissionType.SITE: + target_ids, target_names = self.find_sites(actuator_cfg.target_names_expr) + else: + raise ValueError( + f"Invalid transmission_type: {actuator_cfg.transmission_type}. " + f"Must be TransmissionType.JOINT, TransmissionType.TENDON, or TransmissionType.SITE." + ) + + if len(target_names) == 0: + raise ValueError( + f"No {actuator_cfg.transmission_type}s found for actuator with " + f"expressions: {actuator_cfg.target_names_expr}" + ) + actuator_instance = actuator_cfg.build(self, target_ids, target_names) + actuator_instance.edit_spec(self._spec, target_names) + self._actuators.append(actuator_instance) + + def _add_initial_state_keyframe(self) -> None: + # If joint_pos is None, use existing keyframe from the model. + if self.cfg.init_state.joint_pos is None: + if not self._spec.keys: + raise ValueError( + "joint_pos=None requires the model to have a keyframe, but none exists." + ) + # Keep the existing keyframe, just rename it. + self._spec.keys[0].name = "init_state" + if self.is_fixed_base: + self.root_body.pos[:] = self.cfg.init_state.pos + self.root_body.quat[:] = self.cfg.init_state.rot + return + + qpos_components = [] + + if self._free_joint is not None: + qpos_components.extend([self.cfg.init_state.pos, self.cfg.init_state.rot]) + + joint_pos = None + if self._non_free_joints: + joint_pos = resolve_expr(self.cfg.init_state.joint_pos, self.joint_names, 0.0) + qpos_components.append(joint_pos) + + key_qpos = np.hstack(qpos_components) if qpos_components else np.array([]) + key = self._spec.add_key(name="init_state", qpos=key_qpos.tolist()) + + if self.is_actuated and joint_pos is not None: + name_to_pos = {name: joint_pos[i] for i, name in enumerate(self.joint_names)} + ctrl = [] + for act in self._spec.actuators: + joint_name = act.target + ctrl.append(name_to_pos.get(joint_name, 0.0)) + key.ctrl = np.array(ctrl) + + if self.is_fixed_base: + self.root_body.pos[:] = self.cfg.init_state.pos + self.root_body.quat[:] = self.cfg.init_state.rot + + # Attributes. + + @property + def is_fixed_base(self) -> bool: + """Entity is welded to the world.""" + return self._free_joint is None + + @property + def is_articulated(self) -> bool: + """Entity is articulated (has fixed or actuated joints).""" + return len(self._non_free_joints) > 0 + + @property + def is_actuated(self) -> bool: + """Entity has actuated joints.""" + return len(self._actuators) > 0 + + @property + def has_tendon_actuators(self) -> bool: + """Entity has actuators using tendon transmission.""" + if self.cfg.articulation is None: + return False + return any( + act.transmission_type == TransmissionType.TENDON + for act in self.cfg.articulation.actuators + ) + + @property + def has_site_actuators(self) -> bool: + """Entity has actuators using site transmission.""" + if self.cfg.articulation is None: + return False + return any( + act.transmission_type == TransmissionType.SITE + for act in self.cfg.articulation.actuators + ) + + @property + def is_mocap(self) -> bool: + """Entity root body is a mocap body (only for fixed-base entities).""" + return bool(self.root_body.mocap) if self.is_fixed_base else False + + @property + def spec(self) -> mujoco.MjSpec: + return self._spec + + @property + def data(self) -> EntityData: + return self._data + + @property + def actuators(self) -> list[actuator.Actuator]: + return self._actuators + + @property + def all_joint_names(self) -> tuple[str, ...]: + return tuple(j.name.split("/")[-1] for j in self._all_joints) + + @property + def joint_names(self) -> tuple[str, ...]: + return tuple(j.name.split("/")[-1] for j in self._non_free_joints) + + @property + def body_names(self) -> tuple[str, ...]: + return tuple(b.name.split("/")[-1] for b in self.spec.bodies[1:]) + + @property + def geom_names(self) -> tuple[str, ...]: + return tuple(g.name.split("/")[-1] for g in self.spec.geoms) + + @property + def tendon_names(self) -> tuple[str, ...]: + return tuple(t.name.split("/")[-1] for t in self._spec.tendons) + + @property + def site_names(self) -> tuple[str, ...]: + return tuple(s.name.split("/")[-1] for s in self.spec.sites) + + @property + def actuator_names(self) -> tuple[str, ...]: + return tuple(a.name.split("/")[-1] for a in self.spec.actuators) + + @property + def num_joints(self) -> int: + return len(self.joint_names) + + @property + def num_bodies(self) -> int: + return len(self.body_names) + + @property + def num_geoms(self) -> int: + return len(self.geom_names) + + @property + def num_sites(self) -> int: + return len(self.site_names) + + @property + def num_actuators(self) -> int: + return len(self.actuator_names) + + @property + def root_body(self) -> mujoco.MjsBody: + return self.spec.bodies[1] + + # Methods. + + def find_bodies( + self, name_keys: str | Sequence[str], preserve_order: bool = False + ) -> tuple[list[int], list[str]]: + return resolve_matching_names(name_keys, self.body_names, preserve_order) + + def find_joints( + self, + name_keys: str | Sequence[str], + joint_subset: Sequence[str] | None = None, + preserve_order: bool = False, + ) -> tuple[list[int], list[str]]: + if joint_subset is None: + joint_subset = self.joint_names + return resolve_matching_names(name_keys, joint_subset, preserve_order) + + def find_actuators( + self, + name_keys: str | Sequence[str], + actuator_subset: Sequence[str] | None = None, + preserve_order: bool = False, + ) -> tuple[list[int], list[str]]: + if actuator_subset is None: + actuator_subset = self.actuator_names + return resolve_matching_names(name_keys, actuator_subset, preserve_order) + + def find_tendons( + self, + name_keys: str | Sequence[str], + tendon_subset: Sequence[str] | None = None, + preserve_order: bool = False, + ) -> tuple[list[int], list[str]]: + if tendon_subset is None: + tendon_subset = self.tendon_names + return resolve_matching_names(name_keys, tendon_subset, preserve_order) + + def find_joints_by_actuator_names( + self, + actuator_name_keys: str | Sequence[str], + ) -> tuple[list[int], list[str]]: + # Collect all actuated joint names. + actuated_joint_names_set = set() + for act in self._actuators: + actuated_joint_names_set.update(act.target_names) + + # Filter self.joint_names to only actuated joints, preserving natural order. + actuated_in_natural_order = [ + name for name in self.joint_names if name in actuated_joint_names_set + ] + + # Find joints matching the pattern within actuated joints. + _, matched_joint_names = self.find_joints( + actuator_name_keys, joint_subset=actuated_in_natural_order, preserve_order=False + ) + + # Map joint names back to entity-local indices (indices into self.joint_names). + name_to_entity_idx = {name: i for i, name in enumerate(self.joint_names)} + joint_ids = [name_to_entity_idx[name] for name in matched_joint_names] + return joint_ids, matched_joint_names + + def find_geoms( + self, + name_keys: str | Sequence[str], + geom_subset: Sequence[str] | None = None, + preserve_order: bool = False, + ) -> tuple[list[int], list[str]]: + if geom_subset is None: + geom_subset = self.geom_names + return resolve_matching_names(name_keys, geom_subset, preserve_order) + + def find_sites( + self, + name_keys: str | Sequence[str], + site_subset: Sequence[str] | None = None, + preserve_order: bool = False, + ) -> tuple[list[int], list[str]]: + if site_subset is None: + site_subset = self.site_names + return resolve_matching_names(name_keys, site_subset, preserve_order) + + def compile(self) -> mujoco.MjModel: + """Compile the underlying MjSpec into an MjModel.""" + return self.spec.compile() + + def write_xml(self, xml_path: Path) -> None: + """Write the MjSpec to disk.""" + with open(xml_path, "w") as f: + f.write(self.spec.to_xml()) + + def to_zip(self, path: Path) -> None: + """Write the MjSpec to a zip file.""" + with path.open("wb") as f: + mujoco.MjSpec.to_zip(self.spec, f) + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + indexing = self._compute_indexing(mj_model, device) + self.indexing = indexing + nworld = data.nworld + + for act in self._actuators: + act.initialize(mj_model, model, data, device) + + # Vectorize built-in actuators; we'll loop through custom ones. + builtin_group, custom_actuators = BuiltinActuatorGroup.process(self._actuators) + self._builtin_group = builtin_group + self._custom_actuators = custom_actuators + + # Root state. + root_state_components = [self.cfg.init_state.pos, self.cfg.init_state.rot] + if not self.is_fixed_base: + root_state_components.extend( + [self.cfg.init_state.lin_vel, self.cfg.init_state.ang_vel] + ) + default_root_state = torch.tensor( + sum((tuple(c) for c in root_state_components), ()), + dtype=torch.float, + device=device, + ).repeat(nworld, 1) + + # Joint state. + if self.is_articulated: + if self.cfg.init_state.joint_pos is None: + # Use keyframe joint positions. + key_qpos = mj_model.key("init_state").qpos + nq_root = 7 if not self.is_fixed_base else 0 + default_joint_pos = torch.tensor(key_qpos[nq_root:], device=device)[ + None + ].repeat(nworld, 1) + else: + default_joint_pos = torch.tensor( + resolve_expr(self.cfg.init_state.joint_pos, self.joint_names, 0.0), + device=device, + )[None].repeat(nworld, 1) + default_joint_vel = torch.tensor( + resolve_expr(self.cfg.init_state.joint_vel, self.joint_names, 0.0), + device=device, + )[None].repeat(nworld, 1) + + # Joint limits. + joint_ids_global = torch.tensor( + [j.id for j in self._non_free_joints], device=device + ) + dof_limits = model.jnt_range[:, joint_ids_global] + default_joint_pos_limits = dof_limits.clone() + joint_pos_limits = default_joint_pos_limits.clone() + joint_pos_mean = (joint_pos_limits[..., 0] + joint_pos_limits[..., 1]) / 2 + joint_pos_range = joint_pos_limits[..., 1] - joint_pos_limits[..., 0] + + # Soft limits. + soft_limit_factor = ( + self.cfg.articulation.soft_joint_pos_limit_factor + if self.cfg.articulation + else 1.0 + ) + soft_joint_pos_limits = torch.stack( + [ + joint_pos_mean - 0.5 * joint_pos_range * soft_limit_factor, + joint_pos_mean + 0.5 * joint_pos_range * soft_limit_factor, + ], + dim=-1, + ) + else: + empty_shape = (nworld, 0) + default_joint_pos = torch.empty(*empty_shape, dtype=torch.float, device=device) + default_joint_vel = torch.empty(*empty_shape, dtype=torch.float, device=device) + default_joint_pos_limits = torch.empty( + *empty_shape, 2, dtype=torch.float, device=device + ) + joint_pos_limits = torch.empty(*empty_shape, 2, dtype=torch.float, device=device) + soft_joint_pos_limits = torch.empty( + *empty_shape, 2, dtype=torch.float, device=device + ) + + if self.is_actuated: + joint_pos_target = torch.zeros( + (nworld, self.num_joints), dtype=torch.float, device=device + ) + joint_vel_target = torch.zeros( + (nworld, self.num_joints), dtype=torch.float, device=device + ) + joint_effort_target = torch.zeros( + (nworld, self.num_joints), dtype=torch.float, device=device + ) + else: + joint_pos_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + joint_vel_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + joint_effort_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + + # Only allocate tendon targets if there are actuators using tendon transmission. + if self.has_tendon_actuators: + num_tendons = len(self.tendon_names) + tendon_len_target = torch.zeros( + (nworld, num_tendons), dtype=torch.float, device=device + ) + tendon_vel_target = torch.zeros( + (nworld, num_tendons), dtype=torch.float, device=device + ) + tendon_effort_target = torch.zeros( + (nworld, num_tendons), dtype=torch.float, device=device + ) + else: + tendon_len_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + tendon_vel_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + tendon_effort_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + + # Only allocate site targets if there are actuators using site transmission. + if self.has_site_actuators: + num_sites = len(self.site_names) + site_effort_target = torch.zeros( + (nworld, num_sites), dtype=torch.float, device=device + ) + else: + site_effort_target = torch.empty(nworld, 0, dtype=torch.float, device=device) + + # Encoder bias for simulating encoder calibration errors. + # Shape: (num_envs, num_joints). Defaults to zero (no bias). + if self.is_articulated: + encoder_bias = torch.zeros( + (nworld, self.num_joints), dtype=torch.float, device=device + ) + else: + encoder_bias = torch.empty(nworld, 0, dtype=torch.float, device=device) + + self._data = EntityData( + indexing=indexing, + data=data, + model=model, + device=device, + default_root_state=default_root_state, + default_joint_pos=default_joint_pos, + default_joint_vel=default_joint_vel, + default_joint_pos_limits=default_joint_pos_limits, + joint_pos_limits=joint_pos_limits, + soft_joint_pos_limits=soft_joint_pos_limits, + gravity_vec_w=torch.tensor([0.0, 0.0, -1.0], device=device).repeat(nworld, 1), + forward_vec_b=torch.tensor([1.0, 0.0, 0.0], device=device).repeat(nworld, 1), + is_fixed_base=self.is_fixed_base, + is_articulated=self.is_articulated, + is_actuated=self.is_actuated, + joint_pos_target=joint_pos_target, + joint_vel_target=joint_vel_target, + joint_effort_target=joint_effort_target, + tendon_len_target=tendon_len_target, + tendon_vel_target=tendon_vel_target, + tendon_effort_target=tendon_effort_target, + site_effort_target=site_effort_target, + encoder_bias=encoder_bias, + ) + + def update(self, dt: float) -> None: + for act in self._actuators: + act.update(dt) + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + self.clear_state(env_ids) + + for act in self._actuators: + act.reset(env_ids) + + def write_data_to_sim(self) -> None: + self._apply_actuator_controls() + + def clear_state(self, env_ids: torch.Tensor | slice | None = None) -> None: + self._data.clear_state(env_ids) + + def write_ctrl_to_sim( + self, + ctrl: torch.Tensor, + ctrl_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Write control inputs to the simulation. + + Args: + ctrl: A tensor of control inputs. + ctrl_ids: A tensor of control indices. + env_ids: Optional tensor or slice specifying which environments to set. + If None, all environments are set. + """ + self._data.write_ctrl(ctrl, ctrl_ids, env_ids) + + def write_root_state_to_sim( + self, root_state: torch.Tensor, env_ids: torch.Tensor | slice | None = None + ) -> None: + """Set the root state into the simulation. + + The root state consists of position (3), orientation as a (w, x, y, z) + quaternion (4), linear velocity (3), and angular velocity (3), for a total + of 13 values. All of the quantities are in the world frame. + + Args: + root_state: Tensor of shape (N, 13) where N is the number of environments. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_root_state(root_state, env_ids) + + def write_root_link_pose_to_sim( + self, + root_pose: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the root pose into the simulation. Like `write_root_state_to_sim()` + but only sets position and orientation. + + Args: + root_pose: Tensor of shape (N, 7) where N is the number of environments. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_root_pose(root_pose, env_ids) + + def write_root_link_velocity_to_sim( + self, + root_velocity: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the root link (body origin) velocity into the simulation. Like + `write_root_state_to_sim()` but only sets linear and angular velocity. + + Args: + root_velocity: Tensor of shape (N, 6) where N is the number of environments. + Contains linear velocity (3) at body origin and angular velocity (3), + both in world frame. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_root_velocity(root_velocity, env_ids) + + def write_root_com_velocity_to_sim( + self, + root_velocity: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the root COM velocity into the simulation. + + Args: + root_velocity: Tensor of shape (N, 6) where N is the number of environments. + Contains linear velocity (3) at COM and angular velocity (3), + both in world frame. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_root_com_velocity(root_velocity, env_ids) + + def write_joint_state_to_sim( + self, + position: torch.Tensor, + velocity: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the joint state into the simulation. + + The joint state consists of joint positions and velocities. It does not include + the root state. + + Args: + position: Tensor of shape (N, num_joints) where N is the number of environments. + velocity: Tensor of shape (N, num_joints) where N is the number of environments. + joint_ids: Optional tensor or slice specifying which joints to set. If None, + all joints are set. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_joint_state(position, velocity, joint_ids, env_ids) + + def write_joint_position_to_sim( + self, + position: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the joint positions into the simulation. Like `write_joint_state_to_sim()` + but only sets joint positions. + + Args: + position: Tensor of shape (N, num_joints) where N is the number of environments. + joint_ids: Optional tensor or slice specifying which joints to set. If None, + all joints are set. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_joint_position(position, joint_ids, env_ids) + + def write_joint_velocity_to_sim( + self, + velocity: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ): + """Set the joint velocities into the simulation. Like `write_joint_state_to_sim()` + but only sets joint velocities. + + Args: + velocity: Tensor of shape (N, num_joints) where N is the number of environments. + joint_ids: Optional tensor or slice specifying which joints to set. If None, + all joints are set. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_joint_velocity(velocity, joint_ids, env_ids) + + def set_joint_position_target( + self, + position: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set joint position targets. + + Args: + position: Target joint poisitions with shape (N, num_joints). + joint_ids: Optional joint indices to set. If None, set all joints. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if joint_ids is None: + joint_ids = slice(None) + self._data.joint_pos_target[env_ids, joint_ids] = position + + def set_joint_velocity_target( + self, + velocity: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set joint velocity targets. + + Args: + velocity: Target joint velocities with shape (N, num_joints). + joint_ids: Optional joint indices to set. If None, set all joints. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if joint_ids is None: + joint_ids = slice(None) + self._data.joint_vel_target[env_ids, joint_ids] = velocity + + def set_joint_effort_target( + self, + effort: torch.Tensor, + joint_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set joint effort targets. + + Args: + effort: Target joint efforts with shape (N, num_joints). + joint_ids: Optional joint indices to set. If None, set all joints. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if joint_ids is None: + joint_ids = slice(None) + self._data.joint_effort_target[env_ids, joint_ids] = effort + + def set_tendon_len_target( + self, + length: torch.Tensor, + tendon_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set tendon length targets. + + Args: + length: Target tendon lengths with shape (N, num_tendons). + tendon_ids: Optional tendon indices to set. If None, set all tendons. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if tendon_ids is None: + tendon_ids = slice(None) + self._data.tendon_len_target[env_ids, tendon_ids] = length + + def set_tendon_vel_target( + self, + velocity: torch.Tensor, + tendon_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set tendon velocity targets. + + Args: + velocity: Target tendon velocities with shape (N, num_tendons). + tendon_ids: Optional tendon indices to set. If None, set all tendons. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if tendon_ids is None: + tendon_ids = slice(None) + self._data.tendon_vel_target[env_ids, tendon_ids] = velocity + + def set_tendon_effort_target( + self, + effort: torch.Tensor, + tendon_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set tendon effort targets. + + Args: + effort: Target tendon efforts with shape (N, num_tendons). + tendon_ids: Optional tendon indices to set. If None, set all tendons. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if tendon_ids is None: + tendon_ids = slice(None) + self._data.tendon_effort_target[env_ids, tendon_ids] = effort + + def set_site_effort_target( + self, + effort: torch.Tensor, + site_ids: torch.Tensor | slice | None = None, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set site effort targets. + + Args: + effort: Target site efforts with shape (N, num_sites). + site_ids: Optional site indices to set. If None, set all sites. + env_ids: Optional environment indices. If None, set all environments. + """ + if env_ids is None: + env_ids = slice(None) + if site_ids is None: + site_ids = slice(None) + self._data.site_effort_target[env_ids, site_ids] = effort + + def write_external_wrench_to_sim( + self, + forces: torch.Tensor, + torques: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + body_ids: Sequence[int] | slice | None = None, + ) -> None: + """Apply external wrenches to bodies in the simulation. + + Underneath the hood, this sets the `xfrc_applied` field in the MuJoCo data + structure. The wrenches are specified in the world frame and persist until + the next call to this function or until the simulation is reset. + + Args: + forces: Tensor of shape (N, num_bodies, 3) where N is the number of + environments. + torques: Tensor of shape (N, num_bodies, 3) where N is the number of + environments. + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + body_ids: Optional list of body indices or slice specifying which bodies to + apply the wrenches to. If None, wrenches are applied to all bodies. + """ + self._data.write_external_wrench(forces, torques, body_ids, env_ids) + + def write_mocap_pose_to_sim( + self, + mocap_pose: torch.Tensor, + env_ids: torch.Tensor | slice | None = None, + ) -> None: + """Set the pose of a mocap body into the simulation. + + Args: + mocap_pose: Tensor of shape (N, 7) where N is the number of environments. + Format: [pos_x, pos_y, pos_z, quat_w, quat_x, quat_y, quat_z] + env_ids: Optional tensor or slice specifying which environments to set. If + None, all environments are set. + """ + self._data.write_mocap_pose(mocap_pose, env_ids) + + ## + # Private methods. + ## + + def _compute_indexing(self, model: mujoco.MjModel, device: str) -> EntityIndexing: + bodies = tuple([b for b in self.spec.bodies[1:]]) + joints = self._non_free_joints + geoms = tuple(self.spec.geoms) + sites = tuple(self.spec.sites) + tendons = tuple(self.spec.tendons) + + body_ids = torch.tensor([b.id for b in bodies], dtype=torch.int, device=device) + geom_ids = torch.tensor([g.id for g in geoms], dtype=torch.int, device=device) + site_ids = torch.tensor([s.id for s in sites], dtype=torch.int, device=device) + tendon_ids = torch.tensor([t.id for t in tendons], dtype=torch.int, device=device) + joint_ids = torch.tensor([j.id for j in joints], dtype=torch.int, device=device) + + if self.is_actuated: + actuators = tuple(self.spec.actuators) + ctrl_ids = torch.tensor([a.id for a in actuators], dtype=torch.int, device=device) + else: + actuators = None + ctrl_ids = torch.empty(0, dtype=torch.int, device=device) + + joint_q_adr = [] + joint_v_adr = [] + free_joint_q_adr = [] + free_joint_v_adr = [] + for joint in self.spec.joints: + jnt = model.joint(joint.name) + jnt_type = jnt.type[0] + vadr = jnt.dofadr[0] + qadr = jnt.qposadr[0] + if jnt_type == mujoco.mjtJoint.mjJNT_FREE: + free_joint_v_adr.extend(range(vadr, vadr + 6)) + free_joint_q_adr.extend(range(qadr, qadr + 7)) + else: + joint_v_adr.extend(range(vadr, vadr + dof_width(jnt_type))) + joint_q_adr.extend(range(qadr, qadr + qpos_width(jnt_type))) + joint_q_adr = torch.tensor(joint_q_adr, dtype=torch.int, device=device) + joint_v_adr = torch.tensor(joint_v_adr, dtype=torch.int, device=device) + free_joint_v_adr = torch.tensor(free_joint_v_adr, dtype=torch.int, device=device) + free_joint_q_adr = torch.tensor(free_joint_q_adr, dtype=torch.int, device=device) + + if self.is_fixed_base and self.is_mocap: + mocap_id = int(model.body_mocapid[self.root_body.id]) + else: + mocap_id = None + + return EntityIndexing( + bodies=bodies, + joints=joints, + geoms=geoms, + sites=sites, + tendons=tendons, + actuators=actuators, + body_ids=body_ids, + geom_ids=geom_ids, + site_ids=site_ids, + tendon_ids=tendon_ids, + ctrl_ids=ctrl_ids, + joint_ids=joint_ids, + mocap_id=mocap_id, + joint_q_adr=joint_q_adr, + joint_v_adr=joint_v_adr, + free_joint_q_adr=free_joint_q_adr, + free_joint_v_adr=free_joint_v_adr, + ) + + def _apply_actuator_controls(self) -> None: + self._builtin_group.apply_controls(self._data) + for act in self._custom_actuators: + command = act.get_command(self._data) + self._data.write_ctrl(act.compute(command), act.ctrl_ids) diff --git a/mjlab/src/mjlab/envs/__init__.py b/mjlab/src/mjlab/envs/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..f56adab0d5e39a38a28e10be01234ae614e03c6d --- /dev/null +++ b/mjlab/src/mjlab/envs/__init__.py @@ -0,0 +1,4 @@ +from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv as ManagerBasedRlEnv +from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnvCfg as ManagerBasedRlEnvCfg +from mjlab.envs.types import VecEnvObs as VecEnvObs +from mjlab.envs.types import VecEnvStepReturn as VecEnvStepReturn diff --git a/mjlab/src/mjlab/envs/manager_based_rl_env.py b/mjlab/src/mjlab/envs/manager_based_rl_env.py new file mode 100644 index 0000000000000000000000000000000000000000..133c74ae9fbc10226b91488b10f6b866359abec6 --- /dev/null +++ b/mjlab/src/mjlab/envs/manager_based_rl_env.py @@ -0,0 +1,524 @@ +import math +from dataclasses import dataclass, field +from typing import Any + +import mujoco +import numpy as np +import torch +import warp as wp +from prettytable import PrettyTable + +from mjlab.envs import types +from mjlab.envs.mdp.events import reset_scene_to_default +from mjlab.managers.action_manager import ActionManager, ActionTermCfg +from mjlab.managers.command_manager import ( + CommandManager, + CommandTermCfg, + NullCommandManager, +) +from mjlab.managers.curriculum_manager import ( + CurriculumManager, + CurriculumTermCfg, + NullCurriculumManager, +) +from mjlab.managers.event_manager import EventManager, EventTermCfg +from mjlab.managers.metrics_manager import ( + MetricsManager, + MetricsTermCfg, + NullMetricsManager, +) +from mjlab.managers.observation_manager import ObservationGroupCfg, ObservationManager +from mjlab.managers.reward_manager import RewardManager, RewardTermCfg +from mjlab.managers.termination_manager import TerminationManager, TerminationTermCfg +from mjlab.scene import Scene +from mjlab.scene.scene import SceneCfg +from mjlab.sim import SimulationCfg +from mjlab.sim.sim import Simulation +from mjlab.utils import random as random_utils +from mjlab.utils.logging import print_info +from mjlab.utils.spaces import Box +from mjlab.utils.spaces import Dict as DictSpace +from mjlab.viewer.debug_visualizer import DebugVisualizer +from mjlab.viewer.offscreen_renderer import OffscreenRenderer +from mjlab.viewer.viewer_config import ViewerConfig + + +@dataclass(kw_only=True) +class ManagerBasedRlEnvCfg: + """Configuration for a manager-based RL environment. + + This config defines all aspects of an RL environment: the physical scene, + observations, actions, rewards, terminations, and optional features like + commands and curriculum learning. + + The environment step size is ``sim.mujoco.timestep * decimation``. For example, + with a 2ms physics timestep and decimation=10, the environment runs at 50Hz. + """ + + # Base environment configuration. + + decimation: int + """Number of physics simulation steps per environment step. Higher values mean + coarser control frequency. Environment step duration = physics_dt * decimation.""" + + scene: SceneCfg + """Scene configuration defining terrain, entities, and sensors. The scene + specifies ``num_envs``, the number of parallel environments.""" + + observations: dict[str, ObservationGroupCfg] = field(default_factory=dict) + """Observation groups configuration. Each group (e.g., "actor", "critic") contains + observation terms that are concatenated. Groups can have different settings for + noise, history, and delay.""" + + actions: dict[str, ActionTermCfg] = field(default_factory=dict) + """Action terms configuration. Each term controls a specific entity/aspect + (e.g., joint positions). Action dimensions are concatenated across terms.""" + + events: dict[str, EventTermCfg] = field( + default_factory=lambda: { + "reset_scene_to_default": EventTermCfg( + func=reset_scene_to_default, + mode="reset", + ) + } + ) + """Event terms for domain randomization and state resets. Default includes + ``reset_scene_to_default`` which resets entities to their initial state. + Can be set to empty to disable all events including default reset.""" + + seed: int | None = None + """Random seed for reproducibility. If None, a random seed is used. The actual + seed used is stored back into this field after initialization.""" + + sim: SimulationCfg = field(default_factory=SimulationCfg) + """Simulation configuration including physics timestep, solver iterations, + contact parameters, and NaN guarding.""" + + viewer: ViewerConfig = field(default_factory=ViewerConfig) + """Viewer configuration for rendering (camera position, resolution, etc.).""" + + # RL-specific configuration. + + episode_length_s: float = 0.0 + """Duration of an episode (in seconds). + + Episode length in steps is computed as: + ceil(episode_length_s / (sim.mujoco.timestep * decimation)) + """ + + rewards: dict[str, RewardTermCfg] = field(default_factory=dict) + """Reward terms configuration.""" + + terminations: dict[str, TerminationTermCfg] = field(default_factory=dict) + """Termination terms configuration. If empty, episodes never reset. Use + ``mdp.time_out`` with ``time_out=True`` for episode time limits.""" + + commands: dict[str, CommandTermCfg] = field(default_factory=dict) + """Command generator terms (e.g., velocity targets).""" + + curriculum: dict[str, CurriculumTermCfg] = field(default_factory=dict) + """Curriculum terms for adaptive difficulty.""" + + metrics: dict[str, MetricsTermCfg] = field(default_factory=dict) + """Custom metric terms for logging per-step values as episode averages.""" + + is_finite_horizon: bool = False + """Whether the task has a finite or infinite horizon. Defaults to False (infinite). + + - **Finite horizon (True)**: The time limit defines the task boundary. When reached, + no future value exists beyond it, so the agent receives a terminal done signal. + - **Infinite horizon (False)**: The time limit is an artificial cutoff. The agent + receives a truncated done signal to bootstrap the value of continuing beyond the + limit. + """ + + scale_rewards_by_dt: bool = True + """Whether to multiply rewards by the environment step duration (dt). + + When True (default), reward values are scaled by step_dt to normalize cumulative + episodic rewards across different simulation frequencies. Set to False for + algorithms that expect unscaled reward signals (e.g., HER, static reward scaling). + """ + + +class ManagerBasedRlEnv: + """Manager-based RL environment.""" + + is_vector_env = True + metadata = { + "render_modes": [None, "rgb_array"], + "mujoco_version": mujoco.__version__, + "warp_version": wp.config.version, + } + cfg: ManagerBasedRlEnvCfg + + def __init__( + self, + cfg: ManagerBasedRlEnvCfg, + device: str, + render_mode: str | None = None, + **kwargs, + ) -> None: + # Initialize base environment state. + self.cfg = cfg + if self.cfg.seed is not None: + self.cfg.seed = self.seed(self.cfg.seed) + self._sim_step_counter = 0 + self.extras = {} + self.obs_buf = {} + + # Initialize scene and simulation. + self.scene = Scene(self.cfg.scene, device=device) + self.sim = Simulation( + num_envs=self.scene.num_envs, + cfg=self.cfg.sim, + model=self.scene.compile(), + device=device, + ) + + self.scene.initialize( + mj_model=self.sim.mj_model, + model=self.sim.model, + data=self.sim.data, + ) + + # Wire sensor context to simulation for sense_graph. + if self.scene.sensor_context is not None: + self.sim.set_sensor_context(self.scene.sensor_context) + + # Print environment info. + print_info("") + table = PrettyTable() + table.title = "Base Environment" + table.field_names = ["Property", "Value"] + table.align["Property"] = "l" + table.align["Value"] = "l" + table.add_row(["Number of environments", self.num_envs]) + table.add_row(["Environment device", self.device]) + table.add_row(["Environment seed", self.cfg.seed]) + table.add_row(["Physics step-size", self.physics_dt]) + table.add_row(["Environment step-size", self.step_dt]) + print_info(table.get_string()) + print_info("") + + # Initialize RL-specific state. + self.common_step_counter = 0 + self.episode_length_buf = torch.zeros( + cfg.scene.num_envs, device=device, dtype=torch.long + ) + self.render_mode = render_mode + self._offline_renderer: OffscreenRenderer | None = None + if self.render_mode == "rgb_array": + renderer = OffscreenRenderer( + model=self.sim.mj_model, cfg=self.cfg.viewer, scene=self.scene + ) + renderer.initialize() + self._offline_renderer = renderer + self.metadata["render_fps"] = 1.0 / self.step_dt + + # Load all managers. + self.load_managers() + self.setup_manager_visualizers() + + # Properties. + + @property + def num_envs(self) -> int: + """Number of parallel environments.""" + return self.scene.num_envs + + @property + def physics_dt(self) -> float: + """Physics simulation step size.""" + return self.cfg.sim.mujoco.timestep + + @property + def step_dt(self) -> float: + """Environment step size (physics_dt * decimation).""" + return self.cfg.sim.mujoco.timestep * self.cfg.decimation + + @property + def device(self) -> str: + """Device for computation.""" + return self.sim.device + + @property + def max_episode_length_s(self) -> float: + """Maximum episode length in seconds.""" + return self.cfg.episode_length_s + + @property + def max_episode_length(self) -> int: + """Maximum episode length in steps.""" + return math.ceil(self.max_episode_length_s / self.step_dt) + + @property + def unwrapped(self) -> "ManagerBasedRlEnv": + """Get the unwrapped environment (base case for wrapper chains).""" + return self + + # Methods. + + def setup_manager_visualizers(self) -> None: + self.manager_visualizers = {} + if getattr(self.command_manager, "active_terms", None): + self.manager_visualizers["command_manager"] = self.command_manager + + def load_managers(self) -> None: + """Load and initialize all managers. + + Order is important! Event and command managers must be loaded first, + then action and observation managers, then other RL managers. + """ + # Event manager (required before everything else for domain randomization). + self.event_manager = EventManager(self.cfg.events, self) + print_info(f"[INFO] {self.event_manager}") + + self.sim.expand_model_fields(self.event_manager.domain_randomization_fields) + + # Command manager (must be before observation manager since observations + # may reference commands). + if len(self.cfg.commands) > 0: + self.command_manager = CommandManager(self.cfg.commands, self) + else: + self.command_manager = NullCommandManager() + print_info(f"[INFO] {self.command_manager}") + + # Action and observation managers. + self.action_manager = ActionManager(self.cfg.actions, self) + print_info(f"[INFO] {self.action_manager}") + self.observation_manager = ObservationManager(self.cfg.observations, self) + print_info(f"[INFO] {self.observation_manager}") + + # Other RL-specific managers. + + self.termination_manager = TerminationManager(self.cfg.terminations, self) + print_info(f"[INFO] {self.termination_manager}") + self.reward_manager = RewardManager( + self.cfg.rewards, self, scale_by_dt=self.cfg.scale_rewards_by_dt + ) + print_info(f"[INFO] {self.reward_manager}") + if len(self.cfg.curriculum) > 0: + self.curriculum_manager = CurriculumManager(self.cfg.curriculum, self) + else: + self.curriculum_manager = NullCurriculumManager() + print_info(f"[INFO] {self.curriculum_manager}") + if len(self.cfg.metrics) > 0: + self.metrics_manager = MetricsManager(self.cfg.metrics, self) + else: + self.metrics_manager = NullMetricsManager() + print_info(f"[INFO] {self.metrics_manager}") + + # Configure spaces for the environment. + self._configure_gym_env_spaces() + + # Initialize startup events if defined. + if "startup" in self.event_manager.available_modes: + self.event_manager.apply(mode="startup") + + def reset( + self, + *, + seed: int | None = None, + env_ids: torch.Tensor | None = None, + options: dict[str, Any] | None = None, + ) -> tuple[types.VecEnvObs, dict]: + del options # Unused. + if env_ids is None: + env_ids = torch.arange(self.num_envs, dtype=torch.int64, device=self.device) + if seed is not None: + self.seed(seed) + self._reset_idx(env_ids) + self.scene.write_data_to_sim() + self.sim.forward() + self.sim.sense() + self.obs_buf = self.observation_manager.compute(update_history=True) + return self.obs_buf, self.extras + + def step(self, action: torch.Tensor) -> types.VecEnvStepReturn: + """Run one environment step: apply actions, simulate, compute RL signals. + + **Forward-call placement.** MuJoCo's ``mj_step`` runs forward kinematics + *before* integration, so after stepping, derived quantities (``xpos``, + ``xquat``, ``site_xpos``, ``cvel``, ``sensordata``) lag ``qpos``/``qvel`` + by one physics substep. Rather than calling ``sim.forward()`` twice (once + after the decimation loop and once after the reset block), this method + calls it **once**, right before observation computation. This single call + refreshes derived quantities for *all* envs: non-reset envs pick up + post-decimation kinematics, reset envs pick up post-reset kinematics. + + The tradeoff is that termination and reward managers see derived + quantities that are stale by one physics substep (the last ``mj_step`` + ran ``mj_forward`` from *pre*-integration ``qpos``). In practice, the + staleness is negligible for reward shaping and termination + checks. Critically, the staleness is *consistent*: every env, + every step, always sees the same lag, so the MDP is well-defined + and the value function can learn the correct mapping. + + .. note:: + + Event and command authors do not need to call ``sim.forward()`` + themselves. This method handles it. The only constraint is: do not + read derived quantities (``root_link_pose_w``, ``body_link_vel_w``, + etc.) in the same function that writes state + (``write_root_state_to_sim``, ``write_joint_state_to_sim``, etc.). + See :ref:`faq` for details. + """ + self.action_manager.process_action(action.to(self.device)) + + for _ in range(self.cfg.decimation): + self._sim_step_counter += 1 + self.action_manager.apply_action() + self.scene.write_data_to_sim() + self.sim.step() + self.scene.update(dt=self.physics_dt) + + # Update env counters. + self.episode_length_buf += 1 + self.common_step_counter += 1 + + # Check terminations and compute rewards. + # NOTE: Derived quantities (xpos, xquat, ...) are stale by one physics + # substep here. See the docstring above for why this is acceptable. + self.reset_buf = self.termination_manager.compute() + self.reset_terminated = self.termination_manager.terminated + self.reset_time_outs = self.termination_manager.time_outs + + self.reward_buf = self.reward_manager.compute(dt=self.step_dt) + self.metrics_manager.compute() + + # Reset envs that terminated/timed-out and log the episode info. + reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1) + if len(reset_env_ids) > 0: + self._reset_idx(reset_env_ids) + self.scene.write_data_to_sim() + + # Single forward() call: recompute derived quantities from current + # qpos/qvel for every env. For non-reset envs this resolves the + # one-substep staleness left by mj_step; for reset envs it picks up + # the freshly written reset state. + self.sim.forward() + + self.command_manager.compute(dt=self.step_dt) + + if "interval" in self.event_manager.available_modes: + self.event_manager.apply(mode="interval", dt=self.step_dt) + + self.sim.sense() + self.obs_buf = self.observation_manager.compute(update_history=True) + + return ( + self.obs_buf, + self.reward_buf, + self.reset_terminated, + self.reset_time_outs, + self.extras, + ) + + def render(self) -> np.ndarray | None: + if self.render_mode == "human" or self.render_mode is None: + return None + elif self.render_mode == "rgb_array": + if self._offline_renderer is None: + raise ValueError("Offline renderer not initialized") + debug_callback = ( + self.update_visualizers if hasattr(self, "update_visualizers") else None + ) + self._offline_renderer.update(self.sim.data, debug_vis_callback=debug_callback) + return self._offline_renderer.render() + else: + raise NotImplementedError( + f"Render mode {self.render_mode} is not supported. " + f"Please use: {self.metadata['render_modes']}." + ) + + def close(self) -> None: + if self._offline_renderer is not None: + self._offline_renderer.close() + + @staticmethod + def seed(seed: int = -1) -> int: + if seed == -1: + seed = np.random.randint(0, 10_000) + print_info(f"Setting seed: {seed}") + random_utils.seed_rng(seed) + return seed + + def update_visualizers(self, visualizer: DebugVisualizer) -> None: + for mod in self.manager_visualizers.values(): + mod.debug_vis(visualizer) + for sensor in self.scene.sensors.values(): + sensor.debug_vis(visualizer) + + # Private methods. + + def _configure_gym_env_spaces(self) -> None: + from mjlab.utils.spaces import batch_space + + self.single_observation_space = DictSpace() + for group_name, group_term_names in self.observation_manager.active_terms.items(): + has_concatenated_obs = self.observation_manager.group_obs_concatenate[group_name] + group_dim = self.observation_manager.group_obs_dim[group_name] + if has_concatenated_obs: + assert isinstance(group_dim, tuple) + self.single_observation_space.spaces[group_name] = Box( + shape=group_dim, low=-math.inf, high=math.inf + ) + else: + assert not isinstance(group_dim, tuple) + group_term_cfgs = self.observation_manager._group_obs_term_cfgs[group_name] + # Create a nested dict for this group. + group_space = DictSpace() + for term_name, term_dim, _term_cfg in zip( + group_term_names, group_dim, group_term_cfgs, strict=False + ): + group_space.spaces[term_name] = Box( + shape=term_dim, low=-math.inf, high=math.inf + ) + self.single_observation_space.spaces[group_name] = group_space + + action_dim = sum(self.action_manager.action_term_dim) + self.single_action_space = Box(shape=(action_dim,), low=-math.inf, high=math.inf) + + self.observation_space = batch_space(self.single_observation_space, self.num_envs) + self.action_space = batch_space(self.single_action_space, self.num_envs) + + def _reset_idx(self, env_ids: torch.Tensor | None = None) -> None: + self.curriculum_manager.compute(env_ids=env_ids) + self.sim.reset(env_ids) + self.scene.reset(env_ids) + + if "reset" in self.event_manager.available_modes: + env_step_count = self._sim_step_counter // self.cfg.decimation + self.event_manager.apply( + mode="reset", env_ids=env_ids, global_env_step_count=env_step_count + ) + + # NOTE: This is order sensitive. + self.extras["log"] = dict() + # observation manager. + info = self.observation_manager.reset(env_ids) + self.extras["log"].update(info) + # action manager. + info = self.action_manager.reset(env_ids) + self.extras["log"].update(info) + # rewards manager. + info = self.reward_manager.reset(env_ids) + self.extras["log"].update(info) + # metrics manager. + info = self.metrics_manager.reset(env_ids) + self.extras["log"].update(info) + # curriculum manager. + info = self.curriculum_manager.reset(env_ids) + self.extras["log"].update(info) + # command manager. + info = self.command_manager.reset(env_ids) + self.extras["log"].update(info) + # event manager. + info = self.event_manager.reset(env_ids) + self.extras["log"].update(info) + # termination manager. + info = self.termination_manager.reset(env_ids) + self.extras["log"].update(info) + # reset the episode length buffer. + self.episode_length_buf[env_ids] = 0 diff --git a/mjlab/src/mjlab/envs/types.py b/mjlab/src/mjlab/envs/types.py new file mode 100644 index 0000000000000000000000000000000000000000..7d49acdd254040e71ddce100774b327f1a92fc67 --- /dev/null +++ b/mjlab/src/mjlab/envs/types.py @@ -0,0 +1,6 @@ +from typing import Dict + +import torch + +VecEnvObs = Dict[str, torch.Tensor | Dict[str, torch.Tensor]] +VecEnvStepReturn = tuple[VecEnvObs, torch.Tensor, torch.Tensor, torch.Tensor, dict] diff --git a/mjlab/src/mjlab/managers/__init__.py b/mjlab/src/mjlab/managers/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..2ca6bcb9aac762644c480dea3a808deff88ddd8c --- /dev/null +++ b/mjlab/src/mjlab/managers/__init__.py @@ -0,0 +1,33 @@ +"""Environment managers.""" + +from mjlab.managers.action_manager import ActionManager as ActionManager +from mjlab.managers.action_manager import ActionTerm as ActionTerm +from mjlab.managers.action_manager import ActionTermCfg as ActionTermCfg +from mjlab.managers.command_manager import CommandManager as CommandManager +from mjlab.managers.command_manager import CommandTerm as CommandTerm +from mjlab.managers.command_manager import CommandTermCfg as CommandTermCfg +from mjlab.managers.command_manager import NullCommandManager as NullCommandManager +from mjlab.managers.curriculum_manager import CurriculumManager as CurriculumManager +from mjlab.managers.curriculum_manager import CurriculumTermCfg as CurriculumTermCfg +from mjlab.managers.curriculum_manager import ( + NullCurriculumManager as NullCurriculumManager, +) +from mjlab.managers.event_manager import EventManager as EventManager +from mjlab.managers.event_manager import EventMode as EventMode +from mjlab.managers.event_manager import EventTermCfg as EventTermCfg +from mjlab.managers.manager_base import ManagerBase as ManagerBase +from mjlab.managers.manager_base import ManagerTermBase as ManagerTermBase +from mjlab.managers.manager_base import ManagerTermBaseCfg as ManagerTermBaseCfg +from mjlab.managers.metrics_manager import MetricsManager as MetricsManager +from mjlab.managers.metrics_manager import MetricsTermCfg as MetricsTermCfg +from mjlab.managers.metrics_manager import NullMetricsManager as NullMetricsManager +from mjlab.managers.observation_manager import ( + ObservationGroupCfg as ObservationGroupCfg, +) +from mjlab.managers.observation_manager import ObservationManager as ObservationManager +from mjlab.managers.observation_manager import ObservationTermCfg as ObservationTermCfg +from mjlab.managers.reward_manager import RewardManager as RewardManager +from mjlab.managers.reward_manager import RewardTermCfg as RewardTermCfg +from mjlab.managers.scene_entity_config import SceneEntityCfg as SceneEntityCfg +from mjlab.managers.termination_manager import TerminationManager as TerminationManager +from mjlab.managers.termination_manager import TerminationTermCfg as TerminationTermCfg diff --git a/mjlab/src/mjlab/managers/action_manager.py b/mjlab/src/mjlab/managers/action_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..4bd936f01e67b030d43767fba9969aeabc39b23c --- /dev/null +++ b/mjlab/src/mjlab/managers/action_manager.py @@ -0,0 +1,186 @@ +"""Action manager for processing actions sent to the environment.""" + +from __future__ import annotations + +import abc +from dataclasses import dataclass +from typing import TYPE_CHECKING, Sequence + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBase + +if TYPE_CHECKING: + from mjlab.envs import ManagerBasedRlEnv + + +@dataclass(kw_only=True) +class ActionTermCfg(abc.ABC): + """Configuration for an action term. + + Action terms process raw actions from the policy and apply them to entities + in the scene (e.g., setting joint positions, velocities, or efforts). + """ + + entity_name: str + """Name of the entity in the scene that this action term controls.""" + + clip: dict[str, tuple] | None = None + """Optional clipping bounds per transmission type. Maps transmission name + (e.g., 'position', 'velocity') to (min, max) tuple.""" + + @abc.abstractmethod + def build(self, env: ManagerBasedRlEnv) -> ActionTerm: + """Build the action term from this config.""" + raise NotImplementedError + + +class ActionTerm(ManagerTermBase): + """Base class for action terms. + + The action term is responsible for processing the raw actions sent to the environment + and applying them to the entity managed by the term. + """ + + def __init__(self, cfg: ActionTermCfg, env: ManagerBasedRlEnv): + self.cfg = cfg + super().__init__(env) + self._entity = self._env.scene[self.cfg.entity_name] + + @property + @abc.abstractmethod + def action_dim(self) -> int: + raise NotImplementedError + + @abc.abstractmethod + def process_actions(self, actions: torch.Tensor) -> None: + raise NotImplementedError + + @abc.abstractmethod + def apply_actions(self) -> None: + raise NotImplementedError + + @property + @abc.abstractmethod + def raw_action(self) -> torch.Tensor: + raise NotImplementedError + + +class ActionManager(ManagerBase): + """Manages action processing for the environment. + + The action manager aggregates multiple action terms, each controlling a different + entity or aspect of the simulation. It splits the policy's action tensor and + routes each slice to the appropriate action term. + """ + + def __init__(self, cfg: dict[str, ActionTermCfg], env: ManagerBasedRlEnv): + self.cfg = cfg + super().__init__(env=env) + + # Create buffers to store actions. + self._action = torch.zeros( + (self.num_envs, self.total_action_dim), device=self.device + ) + self._prev_action = torch.zeros_like(self._action) + self._prev_prev_action = torch.zeros_like(self._action) + + def __str__(self) -> str: + msg = f" contains {len(self._term_names)} active terms.\n" + table = PrettyTable() + table.title = f"Active Action Terms (shape: {self.total_action_dim})" + table.field_names = ["Index", "Name", "Dimension"] + table.align["Name"] = "l" + table.align["Dimension"] = "r" + for index, (name, term) in enumerate(self._terms.items()): + table.add_row([index, name, term.action_dim]) + msg += table.get_string() + msg += "\n" + return msg + + # Properties. + + @property + def total_action_dim(self) -> int: + return sum(self.action_term_dim) + + @property + def action_term_dim(self) -> list[int]: + return [term.action_dim for term in self._terms.values()] + + @property + def action(self) -> torch.Tensor: + return self._action + + @property + def prev_action(self) -> torch.Tensor: + return self._prev_action + + @property + def prev_prev_action(self) -> torch.Tensor: + return self._prev_prev_action + + @property + def active_terms(self) -> list[str]: + return self._term_names + + # Methods. + + def get_term(self, name: str) -> ActionTerm: + return self._terms[name] + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> dict[str, float]: + if env_ids is None: + env_ids = slice(None) + # Reset action history. + self._prev_action[env_ids] = 0.0 + self._prev_prev_action[env_ids] = 0.0 + self._action[env_ids] = 0.0 + # Reset action terms. + for term in self._terms.values(): + term.reset(env_ids=env_ids) + return {} + + def process_action(self, action: torch.Tensor) -> None: + if self.total_action_dim != action.shape[1]: + raise ValueError( + f"Invalid action shape, expected: {self.total_action_dim}, received: {action.shape[1]}." + ) + self._prev_prev_action[:] = self._prev_action + self._prev_action[:] = self._action + self._action[:] = action.to(self.device) + # Split and apply. + idx = 0 + for term in self._terms.values(): + term_actions = action[:, idx : idx + term.action_dim] + term.process_actions(term_actions) + idx += term.action_dim + + def apply_action(self) -> None: + for term in self._terms.values(): + term.apply_actions() + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + idx = 0 + for name, term in self._terms.items(): + term_actions = self._action[env_idx, idx : idx + term.action_dim].cpu() + terms.append((name, term_actions.tolist())) + idx += term.action_dim + return terms + + def _prepare_terms(self): + self._term_names: list[str] = list() + self._terms: dict[str, ActionTerm] = dict() + + for term_name, term_cfg in self.cfg.items(): + term_cfg: ActionTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + term = term_cfg.build(self._env) + self._term_names.append(term_name) + self._terms[term_name] = term diff --git a/mjlab/src/mjlab/managers/command_manager.py b/mjlab/src/mjlab/managers/command_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..b044a08e8bc75597ec11b4a3fac506cf6ad43ca0 --- /dev/null +++ b/mjlab/src/mjlab/managers/command_manager.py @@ -0,0 +1,229 @@ +"""Command manager for generating and updating commands.""" + +from __future__ import annotations + +import abc +from dataclasses import dataclass +from typing import TYPE_CHECKING, Any, Sequence + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBase + +if TYPE_CHECKING: + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv + from mjlab.viewer.debug_visualizer import DebugVisualizer + + +@dataclass(kw_only=True) +class CommandTermCfg(abc.ABC): + """Configuration for a command generator term. + + Command terms generate goal commands for the agent (e.g., target velocity, + target position). Commands are automatically resampled at configurable + intervals and can track metrics for logging. + """ + + resampling_time_range: tuple[float, float] + """Time range in seconds for command resampling. When the timer expires, a new + command is sampled and the timer is reset to a value uniformly drawn from + ``[min, max]``. Set both values equal for fixed-interval resampling.""" + + debug_vis: bool = False + """Whether to enable debug visualization for this command term. When True, + the command term's ``_debug_vis_impl`` method is called each frame to render + visual aids (e.g., velocity arrows, target markers).""" + + @abc.abstractmethod + def build(self, env: ManagerBasedRlEnv) -> CommandTerm: + """Build the command term from this config.""" + raise NotImplementedError + + +class CommandTerm(ManagerTermBase): + """Base class for command terms.""" + + def __init__(self, cfg: CommandTermCfg, env: ManagerBasedRlEnv): + self.cfg = cfg + super().__init__(env) + self.metrics = dict() + self.time_left = torch.zeros(self.num_envs, device=self.device) + self.command_counter = torch.zeros( + self.num_envs, device=self.device, dtype=torch.long + ) + + def debug_vis(self, visualizer: "DebugVisualizer") -> None: + if self.cfg.debug_vis: + self._debug_vis_impl(visualizer) + + def _debug_vis_impl(self, visualizer: "DebugVisualizer") -> None: + pass + + @property + @abc.abstractmethod + def command(self): + raise NotImplementedError + + def reset(self, env_ids: torch.Tensor | slice | None) -> dict[str, float]: + assert isinstance(env_ids, torch.Tensor) + extras = {} + for metric_name, metric_value in self.metrics.items(): + extras[metric_name] = torch.mean(metric_value[env_ids]).item() + metric_value[env_ids] = 0.0 + self.command_counter[env_ids] = 0 + self._resample(env_ids) + return extras + + def compute(self, dt: float) -> None: + self._update_metrics() + self.time_left -= dt + resample_env_ids = (self.time_left <= 0.0).nonzero().flatten() + if len(resample_env_ids) > 0: + self._resample(resample_env_ids) + self._update_command() + + def _resample(self, env_ids: torch.Tensor) -> None: + if len(env_ids) != 0: + self.time_left[env_ids] = self.time_left[env_ids].uniform_( + *self.cfg.resampling_time_range + ) + self._resample_command(env_ids) + self.command_counter[env_ids] += 1 + + @abc.abstractmethod + def _update_metrics(self) -> None: + """Update the metrics based on the current state.""" + raise NotImplementedError + + @abc.abstractmethod + def _resample_command(self, env_ids: torch.Tensor) -> None: + """Resample the command for the specified environments.""" + raise NotImplementedError + + @abc.abstractmethod + def _update_command(self) -> None: + """Update the command based on the current state.""" + raise NotImplementedError + + +class CommandManager(ManagerBase): + """Manages command generation for the environment. + + The command manager generates and updates goal commands for the agent (e.g., + target velocity, target position). Commands are resampled at configurable + intervals and can track metrics for logging. + """ + + _env: ManagerBasedRlEnv + + def __init__(self, cfg: dict[str, CommandTermCfg], env: ManagerBasedRlEnv): + self._terms: dict[str, CommandTerm] = dict() + + self.cfg = cfg + super().__init__(env) + self._commands = dict() + + def __str__(self) -> str: + msg = f" contains {len(self._terms.values())} active terms.\n" + table = PrettyTable() + table.title = "Active Command Terms" + table.field_names = ["Index", "Name", "Type"] + table.align["Name"] = "l" + for index, (name, term) in enumerate(self._terms.items()): + table.add_row([index, name, term.__class__.__name__]) + msg += table.get_string() + msg += "\n" + return msg + + def debug_vis(self, visualizer: "DebugVisualizer") -> None: + for term in self._terms.values(): + term.debug_vis(visualizer) + + # Properties. + + @property + def active_terms(self) -> list[str]: + return list(self._terms.keys()) + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + idx = 0 + for name, term in self._terms.items(): + terms.append((name, term.command[env_idx].cpu().tolist())) + idx += term.command.shape[1] + return terms + + def reset(self, env_ids: torch.Tensor | None) -> dict[str, torch.Tensor]: + extras = {} + for name, term in self._terms.items(): + metrics = term.reset(env_ids=env_ids) + for metric_name, metric_value in metrics.items(): + extras[f"Metrics/{name}/{metric_name}"] = metric_value + return extras + + def compute(self, dt: float): + for term in self._terms.values(): + term.compute(dt) + + def get_command(self, name: str) -> torch.Tensor: + return self._terms[name].command + + def get_term(self, name: str) -> CommandTerm: + return self._terms[name] + + def get_term_cfg(self, name: str) -> CommandTermCfg: + return self.cfg[name] + + def _prepare_terms(self): + for term_name, term_cfg in self.cfg.items(): + term_cfg: CommandTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + term = term_cfg.build(self._env) + if not isinstance(term, CommandTerm): + raise TypeError( + f"Returned object for the term {term_name} is not of type CommandType." + ) + self._terms[term_name] = term + + +class NullCommandManager: + """Placeholder for absent command manager that safely no-ops all operations.""" + + def __init__(self): + self.active_terms: list[str] = [] + self._terms: dict[str, Any] = {} + self.cfg = None + + def __str__(self) -> str: + return " (inactive)" + + def __repr__(self) -> str: + return "NullCommandManager()" + + def debug_vis(self, visualizer: "DebugVisualizer") -> None: + pass + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + return [] + + def reset(self, env_ids: torch.Tensor | None = None) -> dict[str, torch.Tensor]: + return {} + + def compute(self, dt: float) -> None: + pass + + def get_command(self, name: str) -> None: + return None + + def get_term(self, name: str) -> None: + return None + + def get_term_cfg(self, name: str) -> None: + return None diff --git a/mjlab/src/mjlab/managers/curriculum_manager.py b/mjlab/src/mjlab/managers/curriculum_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..d34b25aa60c8566e711648cd2d19fddc9d50a9b1 --- /dev/null +++ b/mjlab/src/mjlab/managers/curriculum_manager.py @@ -0,0 +1,155 @@ +"""Curriculum manager for updating environment quantities subject to a training curriculum.""" + +from __future__ import annotations + +from copy import deepcopy +from dataclasses import dataclass +from typing import TYPE_CHECKING, Any, Sequence + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBaseCfg + +if TYPE_CHECKING: + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv + + +@dataclass(kw_only=True) +class CurriculumTermCfg(ManagerTermBaseCfg): + """Configuration for a curriculum term. + + Curriculum terms modify environment parameters during training to implement + curriculum learning strategies (e.g., gradually increasing task difficulty). + """ + + pass + + +class CurriculumManager(ManagerBase): + """Manages curriculum learning for the environment. + + The curriculum manager updates environment parameters during training based + on agent performance. Each term can modify different aspects of the task + difficulty (e.g., terrain complexity, command ranges). + """ + + _env: ManagerBasedRlEnv + + def __init__(self, cfg: dict[str, CurriculumTermCfg], env: ManagerBasedRlEnv): + self._term_names: list[str] = list() + self._term_cfgs: list[CurriculumTermCfg] = list() + self._class_term_cfgs: list[CurriculumTermCfg] = list() + + self.cfg = deepcopy(cfg) + super().__init__(env) + + self._curriculum_state = dict() + for term_name in self._term_names: + self._curriculum_state[term_name] = None + + def __str__(self) -> str: + msg = f" contains {len(self._term_names)} active terms.\n" + table = PrettyTable() + table.title = "Active Curriculum Terms" + table.field_names = ["Index", "Name"] + table.align["Name"] = "l" + for index, name in enumerate(self._term_names): + table.add_row([index, name]) + msg += table.get_string() + msg += "\n" + return msg + + # Properties. + + @property + def active_terms(self) -> list[str]: + return self._term_names + + # Methods. + + def get_term_cfg(self, term_name: str) -> CurriculumTermCfg: + if term_name not in self._term_names: + raise ValueError(f"Term '{term_name}' not found in active terms.") + return self._term_cfgs[self._term_names.index(term_name)] + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + for term_name, term_state in self._curriculum_state.items(): + if term_state is not None: + data = [] + if isinstance(term_state, dict): + for _key, value in term_state.items(): + if isinstance(value, torch.Tensor): + value = value.item() + terms[term_name].append(value) + else: + if isinstance(term_state, torch.Tensor): + term_state = term_state.item() + data.append(term_state) + terms.append((term_name, data)) + return terms + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> dict[str, float]: + extras = {} + for term_name, term_state in self._curriculum_state.items(): + if term_state is not None: + if isinstance(term_state, dict): + for key, value in term_state.items(): + if isinstance(value, torch.Tensor): + value = value.item() + extras[f"Curriculum/{term_name}/{key}"] = value + else: + if isinstance(term_state, torch.Tensor): + term_state = term_state.item() + extras[f"Curriculum/{term_name}"] = term_state + for term_cfg in self._class_term_cfgs: + term_cfg.func.reset(env_ids=env_ids) + return extras + + def compute(self, env_ids: torch.Tensor | slice | None = None): + if env_ids is None: + env_ids = slice(None) + for name, term_cfg in zip(self._term_names, self._term_cfgs, strict=False): + state = term_cfg.func(self._env, env_ids, **term_cfg.params) + self._curriculum_state[name] = state + + def _prepare_terms(self): + for term_name, term_cfg in self.cfg.items(): + term_cfg: CurriculumTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + self._resolve_common_term_cfg(term_name, term_cfg) + self._term_names.append(term_name) + self._term_cfgs.append(term_cfg) + if hasattr(term_cfg.func, "reset") and callable(term_cfg.func.reset): + self._class_term_cfgs.append(term_cfg) + + +class NullCurriculumManager: + """Placeholder for absent curriculum manager that safely no-ops all operations.""" + + def __init__(self): + self.active_terms: list[str] = [] + self._curriculum_state: dict[str, Any] = {} + self.cfg = None + + def __str__(self) -> str: + return " (inactive)" + + def __repr__(self) -> str: + return "NullCurriculumManager()" + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + return [] + + def reset(self, env_ids: torch.Tensor | None = None) -> dict[str, float]: + return {} + + def compute(self, env_ids: torch.Tensor | None = None) -> None: + pass diff --git a/mjlab/src/mjlab/managers/manager_base.py b/mjlab/src/mjlab/managers/manager_base.py new file mode 100644 index 0000000000000000000000000000000000000000..049df2d4cd98d4d3ad71a03c85da6f124dc36391 --- /dev/null +++ b/mjlab/src/mjlab/managers/manager_base.py @@ -0,0 +1,139 @@ +from __future__ import annotations + +import abc +import inspect +from collections.abc import Sequence +from dataclasses import dataclass, field +from typing import TYPE_CHECKING, Any + +import torch + +from mjlab.managers.scene_entity_config import SceneEntityCfg + +if TYPE_CHECKING: + from mjlab.envs import ManagerBasedRlEnv + + +@dataclass +class ManagerTermBaseCfg: + """Base configuration for manager terms. + + This is the base config for terms in observation, reward, termination, curriculum, + and event managers. It provides a common interface for specifying a callable + and its parameters. + + The ``func`` field accepts either a function or a class: + + **Function-based terms** are simpler and suitable for stateless computations: + + .. code-block:: python + + RewardTermCfg(func=mdp.joint_torques_l2, weight=-0.01) + + **Class-based terms** are instantiated with ``(cfg, env)`` and useful when you need + to: + + - Cache computed values at initialization (e.g., resolve regex patterns to indices) + - Maintain state across calls + - Perform expensive setup once rather than every call + + .. code-block:: python + + class posture: + def __init__(self, cfg: RewardTermCfg, env: ManagerBasedRlEnv): + # Resolve std dict to tensor once at init + self.std = resolve_std_to_tensor(cfg.params["std"], env) + + def __call__(self, env, **kwargs) -> torch.Tensor: + # Use cached self.std + return compute_posture_reward(env, self.std) + + RewardTermCfg(func=posture, params={"std": {".*knee.*": 0.3}}, weight=1.0) + + Class-based terms can optionally implement ``reset(env_ids)`` for per-episode state. + """ + + func: Any + """The callable that computes this term's value. Can be a function or a class. + Classes are auto-instantiated with ``(cfg=term_cfg, env=env)``.""" + + params: dict[str, Any] = field(default_factory=lambda: {}) + """Additional keyword arguments passed to func when called.""" + + +class ManagerTermBase: + def __init__(self, env: ManagerBasedRlEnv): + self._env = env + + # Properties. + + @property + def num_envs(self) -> int: + return self._env.num_envs + + @property + def device(self) -> str: + return self._env.device + + @property + def name(self) -> str: + return self.__class__.__name__ + + # Methods. + + def reset(self, env_ids: torch.Tensor | slice | None) -> Any: + """Resets the manager term.""" + del env_ids # Unused. + pass + + def __call__(self, *args, **kwargs) -> Any: + """Returns the value of the term required by the manager.""" + raise NotImplementedError + + +class ManagerBase(abc.ABC): + """Base class for all managers.""" + + def __init__(self, env: ManagerBasedRlEnv): + self._env = env + + self._prepare_terms() + + # Properties. + + @property + def num_envs(self) -> int: + return self._env.num_envs + + @property + def device(self) -> str: + return self._env.device + + @property + @abc.abstractmethod + def active_terms(self) -> list[str] | dict[Any, list[str]]: + raise NotImplementedError + + # Methods. + + def reset(self, env_ids: torch.Tensor) -> dict[str, Any]: + """Resets the manager and returns logging info for the current step.""" + del env_ids # Unused. + return {} + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + raise NotImplementedError + + @abc.abstractmethod + def _prepare_terms(self): + raise NotImplementedError + + def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg): + del term_name # Unused. + for value in term_cfg.params.values(): + if isinstance(value, SceneEntityCfg): + value.resolve(self._env.scene) + if inspect.isclass(term_cfg.func): + term_cfg.func = term_cfg.func(cfg=term_cfg, env=self._env) diff --git a/mjlab/src/mjlab/managers/metrics_manager.py b/mjlab/src/mjlab/managers/metrics_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..c2eff70377612b76f7955b1f882e065dca78dd62 --- /dev/null +++ b/mjlab/src/mjlab/managers/metrics_manager.py @@ -0,0 +1,144 @@ +"""Metrics manager for logging custom per-step metrics during training.""" + +from __future__ import annotations + +from copy import deepcopy +from dataclasses import dataclass +from typing import TYPE_CHECKING, Sequence + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBaseCfg + +if TYPE_CHECKING: + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv + + +@dataclass(kw_only=True) +class MetricsTermCfg(ManagerTermBaseCfg): + """Configuration for a metrics term.""" + + pass + + +class MetricsManager(ManagerBase): + """Accumulates per-step metric values, reports episode averages. + + Unlike rewards, metrics have no weight, no dt scaling, and no + normalization by episode length. Episode values are true per-step + averages (sum / step_count), so a metric in [0,1] stays in [0,1] + in the logger. + """ + + _env: ManagerBasedRlEnv + + def __init__(self, cfg: dict[str, MetricsTermCfg], env: ManagerBasedRlEnv): + self._term_names: list[str] = list() + self._term_cfgs: list[MetricsTermCfg] = list() + self._class_term_cfgs: list[MetricsTermCfg] = list() + + self.cfg = deepcopy(cfg) + super().__init__(env=env) + + self._episode_sums: dict[str, torch.Tensor] = {} + for term_name in self._term_names: + self._episode_sums[term_name] = torch.zeros( + self.num_envs, dtype=torch.float, device=self.device + ) + self._step_count = torch.zeros(self.num_envs, dtype=torch.long, device=self.device) + self._step_values = torch.zeros( + (self.num_envs, len(self._term_names)), dtype=torch.float, device=self.device + ) + + def __str__(self) -> str: + msg = f" contains {len(self._term_names)} active terms.\n" + table = PrettyTable() + table.title = "Active Metrics Terms" + table.field_names = ["Index", "Name"] + table.align["Name"] = "l" + for index, name in enumerate(self._term_names): + table.add_row([index, name]) + msg += table.get_string() + msg += "\n" + return msg + + # Properties. + + @property + def active_terms(self) -> list[str]: + return self._term_names + + # Methods. + + def reset( + self, env_ids: torch.Tensor | slice | None = None + ) -> dict[str, torch.Tensor]: + if env_ids is None: + env_ids = slice(None) + extras = {} + counts = self._step_count[env_ids].float() + # Avoid division by zero for envs that haven't stepped. + safe_counts = torch.clamp(counts, min=1.0) + for key in self._episode_sums: + episode_avg = torch.mean(self._episode_sums[key][env_ids] / safe_counts) + extras["Episode_Metrics/" + key] = episode_avg + self._episode_sums[key][env_ids] = 0.0 + self._step_count[env_ids] = 0 + for term_cfg in self._class_term_cfgs: + term_cfg.func.reset(env_ids=env_ids) + return extras + + def compute(self) -> None: + self._step_count += 1 + for term_idx, (name, term_cfg) in enumerate( + zip(self._term_names, self._term_cfgs, strict=False) + ): + value = term_cfg.func(self._env, **term_cfg.params) + self._episode_sums[name] += value + self._step_values[:, term_idx] = value + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + for idx, name in enumerate(self._term_names): + terms.append((name, [self._step_values[env_idx, idx].cpu().item()])) + return terms + + def _prepare_terms(self): + for term_name, term_cfg in self.cfg.items(): + term_cfg: MetricsTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + self._resolve_common_term_cfg(term_name, term_cfg) + self._term_names.append(term_name) + self._term_cfgs.append(term_cfg) + if hasattr(term_cfg.func, "reset") and callable(term_cfg.func.reset): + self._class_term_cfgs.append(term_cfg) + + +class NullMetricsManager: + """Placeholder for absent metrics manager that safely no-ops all operations.""" + + def __init__(self): + self.active_terms: list[str] = [] + self.cfg = None + + def __str__(self) -> str: + return " (inactive)" + + def __repr__(self) -> str: + return "NullMetricsManager()" + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + return [] + + def reset(self, env_ids: torch.Tensor | None = None) -> dict[str, float]: + return {} + + def compute(self) -> None: + pass diff --git a/mjlab/src/mjlab/managers/observation_manager.py b/mjlab/src/mjlab/managers/observation_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..f4682f51b331ecc31c02a965b683ec5e03d01d4b --- /dev/null +++ b/mjlab/src/mjlab/managers/observation_manager.py @@ -0,0 +1,485 @@ +"""Observation manager for computing observations.""" + +from copy import deepcopy +from dataclasses import dataclass +from typing import Literal, Sequence + +import numpy as np +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBaseCfg +from mjlab.utils.buffers import CircularBuffer, DelayBuffer +from mjlab.utils.noise import noise_cfg, noise_model +from mjlab.utils.noise.noise_cfg import NoiseCfg, NoiseModelCfg + + +@dataclass +class ObservationTermCfg(ManagerTermBaseCfg): + """Configuration for an observation term. + + Processing pipeline: compute → noise → clip → scale → delay → history. + Delay models sensor latency. History provides temporal context. Both are optional + and can be combined. + """ + + noise: NoiseCfg | NoiseModelCfg | None = None + """Noise model to apply to the observation.""" + + clip: tuple[float, float] | None = None + """Range (min, max) to clip the observation values.""" + + scale: tuple[float, ...] | float | torch.Tensor | None = None + """Scaling factor(s) to multiply the observation by.""" + + delay_min_lag: int = 0 + """Minimum lag (in steps) for delayed observations. Lag sampled uniformly from + [min_lag, max_lag]. Convert to ms: lag * (1000 / control_hz).""" + + delay_max_lag: int = 0 + """Maximum lag (in steps) for delayed observations. Use min=max for constant delay.""" + + delay_per_env: bool = True + """If True, each environment samples its own lag. If False, all environments share + the same lag at each step.""" + + delay_hold_prob: float = 0.0 + """Probability of reusing the previous lag instead of resampling. Useful for + temporally correlated latency patterns.""" + + delay_update_period: int = 0 + """Resample lag every N steps (models multi-rate sensors). If 0, update every step.""" + + delay_per_env_phase: bool = True + """If True and update_period > 0, stagger update timing across envs to avoid + synchronized resampling.""" + + history_length: int = 0 + """Number of past observations to keep in history. 0 = no history.""" + + flatten_history_dim: bool = True + """Whether to flatten the history dimension into observation. + + When True and concatenate_terms=True, uses term-major ordering: + [A_t0, A_t1, ..., A_tH-1, B_t0, B_t1, ..., B_tH-1, ...] + See docs/source/observation.rst for details on ordering.""" + + +@dataclass +class ObservationGroupCfg: + """Configuration for an observation group. + + An observation group bundles multiple observation terms together. Groups are + typically used to separate observations for different purposes (e.g., "actor" + for the actor, "critic" for the value function). + """ + + terms: dict[str, ObservationTermCfg] + """Dictionary mapping term names to their configurations.""" + + concatenate_terms: bool = True + """Whether to concatenate all terms into a single tensor. If False, returns + a dict mapping term names to their individual tensors.""" + + concatenate_dim: int = -1 + """Dimension along which to concatenate terms. Default -1 (last dimension).""" + + enable_corruption: bool = False + """Whether to apply noise corruption to observations. Set to True during + training for domain randomization, False during evaluation.""" + + history_length: int | None = None + """Group-level history length override. If set, applies to all terms in + this group. If None, each term uses its own ``history_length`` setting.""" + + flatten_history_dim: bool = True + """Whether to flatten history into the observation dimension. If True, + observations have shape ``(num_envs, obs_dim * history_length)``. If False, + shape is ``(num_envs, history_length, obs_dim)``.""" + + nan_policy: Literal["disabled", "warn", "sanitize", "error"] = "disabled" + """NaN/Inf handling policy for observations in this group. + + - 'disabled': No checks (default, fastest) + - 'warn': Log warning with term name and env IDs, then sanitize (debugging) + - 'sanitize': Silent sanitization to 0.0 like reward manager (safe for production) + - 'error': Raise ValueError on NaN/Inf (strict development mode) + """ + + nan_check_per_term: bool = True + """If True, check each observation term individually to identify NaN source. + If False, check only the final concatenated output (faster but less informative). + Only applies when nan_policy != 'disabled'.""" + + +class ObservationManager(ManagerBase): + """Manages observation computation for the environment. + + The observation manager computes observations from multiple terms organized + into groups. Each term can have noise, clipping, scaling, delay, and history + applied. Groups can optionally concatenate their terms into a single tensor. + """ + + def __init__(self, cfg: dict[str, ObservationGroupCfg], env): + self.cfg = deepcopy(cfg) + super().__init__(env=env) + + self._group_obs_dim: dict[str, tuple[int, ...] | list[tuple[int, ...]]] = dict() + + for group_name, group_term_dims in self._group_obs_term_dim.items(): + if self._group_obs_concatenate[group_name]: + term_dims = torch.stack( + [torch.tensor(dims, device="cpu") for dims in group_term_dims], dim=0 + ) + if len(term_dims.shape) > 1: + if self._group_obs_concatenate_dim[group_name] >= 0: + dim = self._group_obs_concatenate_dim[group_name] - 1 + else: + dim = self._group_obs_concatenate_dim[group_name] + dim_sum = torch.sum(term_dims[:, dim], dim=0) + term_dims[0, dim] = dim_sum + term_dims = term_dims[0] + else: + term_dims = torch.sum(term_dims, dim=0) + self._group_obs_dim[group_name] = tuple(term_dims.tolist()) + else: + self._group_obs_dim[group_name] = group_term_dims + + self._obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] | None = None + + def __str__(self) -> str: + msg = f" contains {len(self._group_obs_term_names)} groups.\n" + for group_name, group_dim in self._group_obs_dim.items(): + table = PrettyTable() + table.title = f"Active Observation Terms in Group: '{group_name}'" + if self._group_obs_concatenate[group_name]: + table.title += f" (shape: {group_dim})" # type: ignore + table.field_names = ["Index", "Name", "Shape"] + table.align["Name"] = "l" + obs_terms = zip( + self._group_obs_term_names[group_name], + self._group_obs_term_dim[group_name], + self._group_obs_term_cfgs[group_name], + strict=False, + ) + for index, (name, dims, term_cfg) in enumerate(obs_terms): + if term_cfg.history_length > 0 and term_cfg.flatten_history_dim: + # Flattened history: show (9,) ← 3×(3,) + original_size = int(np.prod(dims)) // term_cfg.history_length + original_shape = (original_size,) if len(dims) == 1 else dims[1:] + shape_str = f"{dims} ← {term_cfg.history_length}×{original_shape}" + else: + shape_str = str(tuple(dims)) + table.add_row([index, name, shape_str]) + msg += table.get_string() + msg += "\n" + return msg + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + + if self._obs_buffer is None: + self.compute() + assert self._obs_buffer is not None + obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] = self._obs_buffer + + for group_name, _ in self.group_obs_dim.items(): + if not self.group_obs_concatenate[group_name]: + buffers = obs_buffer[group_name] + assert isinstance(buffers, dict) + for name, term in buffers.items(): + terms.append((group_name + "-" + name, term[env_idx].cpu().tolist())) # type: ignore[unsupported-operator] + continue + + idx = 0 + data = obs_buffer[group_name] + assert isinstance(data, torch.Tensor) + for name, shape in zip( + self._group_obs_term_names[group_name], + self._group_obs_term_dim[group_name], + strict=False, + ): + data_length = np.prod(shape) + term = data[env_idx, idx : idx + data_length] + terms.append((group_name + "-" + name, term.cpu().tolist())) + idx += data_length + + return terms + + # Properties. + + @property + def active_terms(self) -> dict[str, list[str]]: + return self._group_obs_term_names + + @property + def group_obs_dim(self) -> dict[str, tuple[int, ...] | list[tuple[int, ...]]]: + return self._group_obs_dim + + @property + def group_obs_term_dim(self) -> dict[str, list[tuple[int, ...]]]: + return self._group_obs_term_dim + + @property + def group_obs_concatenate(self) -> dict[str, bool]: + return self._group_obs_concatenate + + # Methods. + + def get_term_cfg(self, group_name: str, term_name: str) -> ObservationTermCfg: + if group_name not in self._group_obs_term_names: + raise ValueError(f"Group '{group_name}' not found in active groups.") + if term_name not in self._group_obs_term_names[group_name]: + raise ValueError(f"Term '{term_name}' not found in group '{group_name}'.") + index = self._group_obs_term_names[group_name].index(term_name) + return self._group_obs_term_cfgs[group_name][index] + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> dict[str, float]: + # Invalidate cache since reset envs will have different observations. + self._obs_buffer = None + + for group_name, group_cfg in self._group_obs_class_term_cfgs.items(): + for term_cfg in group_cfg: + term_cfg.func.reset(env_ids=env_ids) + for term_name in self._group_obs_term_names[group_name]: + batch_ids = None if isinstance(env_ids, slice) else env_ids + if term_name in self._group_obs_term_delay_buffer[group_name]: + self._group_obs_term_delay_buffer[group_name][term_name].reset( + batch_ids=batch_ids + ) + if term_name in self._group_obs_term_history_buffer[group_name]: + self._group_obs_term_history_buffer[group_name][term_name].reset( + batch_ids=batch_ids + ) + for mod in self._group_obs_class_instances.values(): + mod.reset(env_ids=env_ids) + return {} + + def _check_and_handle_nans( + self, tensor: torch.Tensor, context: str, policy: str + ) -> torch.Tensor: + """Check for NaN/Inf and handle according to policy. + + Args: + tensor: Observation tensor to check. + context: Context string for error/warning messages (e.g., "actor/base_lin_vel"). + policy: NaN handling policy ("disabled", "warn", "sanitize", "error"). + + Returns: + The tensor, potentially sanitized depending on policy. + + Raises: + ValueError: If policy is "error" and NaN/Inf detected. + """ + if policy == "disabled": + return tensor + + has_nan = torch.isnan(tensor).any() + has_inf = torch.isinf(tensor).any() + + if not (has_nan or has_inf): + return tensor + + if policy == "error": + nan_mask = torch.isnan(tensor).any(dim=-1) | torch.isinf(tensor).any(dim=-1) + nan_env_ids = torch.where(nan_mask)[0].cpu().tolist() + raise ValueError( + f"NaN/Inf detected in observation '{context}' " + f"for environments: {nan_env_ids[:10]}" + ) + + if policy == "warn": + nan_mask = torch.isnan(tensor).any(dim=-1) | torch.isinf(tensor).any(dim=-1) + nan_env_ids = torch.where(nan_mask)[0].cpu().tolist() + print( + f"[ObservationManager] NaN/Inf in '{context}' " + f"(envs: {nan_env_ids[:5]}). Sanitizing to 0." + ) + + # Sanitize (applies to both "warn" and "sanitize" policies). + return torch.nan_to_num(tensor, nan=0.0, posinf=0.0, neginf=0.0) + + def compute( + self, update_history: bool = False + ) -> dict[str, torch.Tensor | dict[str, torch.Tensor]]: + # Return cached observations if not updating and cache exists. + # This prevents double-pushing to delay buffers when compute() is called + # multiple times per control step (e.g., in get_observations() after step()). + if not update_history and self._obs_buffer is not None: + return self._obs_buffer + + obs_buffer: dict[str, torch.Tensor | dict[str, torch.Tensor]] = dict() + for group_name in self._group_obs_term_names: + obs_buffer[group_name] = self.compute_group(group_name, update_history) + self._obs_buffer = obs_buffer + return obs_buffer + + def compute_group( + self, group_name: str, update_history: bool = False + ) -> torch.Tensor | dict[str, torch.Tensor]: + group_cfg = self.cfg[group_name] + group_term_names = self._group_obs_term_names[group_name] + group_obs: dict[str, torch.Tensor] = {} + obs_terms = zip( + group_term_names, self._group_obs_term_cfgs[group_name], strict=False + ) + for term_name, term_cfg in obs_terms: + obs: torch.Tensor = term_cfg.func(self._env, **term_cfg.params).clone() + if isinstance(term_cfg.noise, noise_cfg.NoiseCfg): + obs = term_cfg.noise.apply(obs) + elif isinstance(term_cfg.noise, noise_cfg.NoiseModelCfg): + obs = self._group_obs_class_instances[term_name](obs) + if term_cfg.clip: + obs = obs.clip_(min=term_cfg.clip[0], max=term_cfg.clip[1]) + if term_cfg.scale is not None: + scale = term_cfg.scale + assert isinstance(scale, torch.Tensor) + obs = obs.mul_(scale) + + # Check for NaN/Inf before delay/history buffers (per-term checking). + if group_cfg.nan_check_per_term and group_cfg.nan_policy != "disabled": + obs = self._check_and_handle_nans( + obs, context=f"{group_name}/{term_name}", policy=group_cfg.nan_policy + ) + + if term_cfg.delay_max_lag > 0: + delay_buffer = self._group_obs_term_delay_buffer[group_name][term_name] + delay_buffer.append(obs) + obs = delay_buffer.compute() + if term_cfg.history_length > 0: + circular_buffer = self._group_obs_term_history_buffer[group_name][term_name] + if update_history or not circular_buffer.is_initialized: + circular_buffer.append(obs) + + if term_cfg.flatten_history_dim: + group_obs[term_name] = circular_buffer.buffer.reshape(self._env.num_envs, -1) + else: + group_obs[term_name] = circular_buffer.buffer + else: + group_obs[term_name] = obs + + # Final NaN check for non-per-term checking. + if not group_cfg.nan_check_per_term and group_cfg.nan_policy != "disabled": + if self._group_obs_concatenate[group_name]: + # Will check after concatenation below. + pass + else: + for term_name in group_obs: + group_obs[term_name] = self._check_and_handle_nans( + group_obs[term_name], + context=f"{group_name}/{term_name}", + policy=group_cfg.nan_policy, + ) + + if self._group_obs_concatenate[group_name]: + result = torch.cat( + list(group_obs.values()), dim=self._group_obs_concatenate_dim[group_name] + ) + # Final check for concatenated result (non-per-term checking). + if not group_cfg.nan_check_per_term and group_cfg.nan_policy != "disabled": + result = self._check_and_handle_nans( + result, context=group_name, policy=group_cfg.nan_policy + ) + return result + return group_obs + + def _prepare_terms(self) -> None: + self._group_obs_term_names: dict[str, list[str]] = dict() + self._group_obs_term_dim: dict[str, list[tuple[int, ...]]] = dict() + self._group_obs_term_cfgs: dict[str, list[ObservationTermCfg]] = dict() + self._group_obs_class_term_cfgs: dict[str, list[ObservationTermCfg]] = dict() + self._group_obs_concatenate: dict[str, bool] = dict() + self._group_obs_concatenate_dim: dict[str, int] = dict() + self._group_obs_class_instances: dict[str, noise_model.NoiseModel] = {} + self._group_obs_term_delay_buffer: dict[str, dict[str, DelayBuffer]] = dict() + self._group_obs_term_history_buffer: dict[str, dict[str, CircularBuffer]] = dict() + + for group_name, group_cfg in self.cfg.items(): + group_cfg: ObservationGroupCfg | None + if group_cfg is None: + print(f"group: {group_name} set to None, skipping...") + continue + + self._group_obs_term_names[group_name] = list() + self._group_obs_term_dim[group_name] = list() + self._group_obs_term_cfgs[group_name] = list() + self._group_obs_class_term_cfgs[group_name] = list() + group_entry_delay_buffer: dict[str, DelayBuffer] = dict() + group_entry_history_buffer: dict[str, CircularBuffer] = dict() + + self._group_obs_concatenate[group_name] = group_cfg.concatenate_terms + self._group_obs_concatenate_dim[group_name] = ( + group_cfg.concatenate_dim + 1 + if group_cfg.concatenate_dim >= 0 + else group_cfg.concatenate_dim + ) + + for term_name, term_cfg in group_cfg.terms.items(): + term_cfg: ObservationTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + + # NOTE: This deepcopy is important to avoid cross-group contamination of term + # configs. + term_cfg = deepcopy(term_cfg) + self._resolve_common_term_cfg(term_name, term_cfg) + + if not group_cfg.enable_corruption: + term_cfg.noise = None + if group_cfg.history_length is not None: + term_cfg.history_length = group_cfg.history_length + term_cfg.flatten_history_dim = group_cfg.flatten_history_dim + self._group_obs_term_names[group_name].append(term_name) + self._group_obs_term_cfgs[group_name].append(term_cfg) + if hasattr(term_cfg.func, "reset") and callable(term_cfg.func.reset): + self._group_obs_class_term_cfgs[group_name].append(term_cfg) + + obs_dims = tuple(term_cfg.func(self._env, **term_cfg.params).shape) + + if term_cfg.scale is not None: + term_cfg.scale = torch.tensor( + term_cfg.scale, dtype=torch.float, device=self._env.device + ) + + if term_cfg.noise is not None and isinstance( + term_cfg.noise, noise_cfg.NoiseModelCfg + ): + noise_model_cls = term_cfg.noise.class_type + assert issubclass(noise_model_cls, noise_model.NoiseModel), ( + f"Class type for observation term '{term_name}' NoiseModelCfg" + f" is not a subclass of 'NoiseModel'. Received: '{type(noise_model_cls)}'." + ) + self._group_obs_class_instances[term_name] = noise_model_cls( + term_cfg.noise, num_envs=self._env.num_envs, device=self._env.device + ) + + if term_cfg.delay_max_lag > 0: + group_entry_delay_buffer[term_name] = DelayBuffer( + min_lag=term_cfg.delay_min_lag, + max_lag=term_cfg.delay_max_lag, + batch_size=self._env.num_envs, + device=self._env.device, + per_env=term_cfg.delay_per_env, + hold_prob=term_cfg.delay_hold_prob, + update_period=term_cfg.delay_update_period, + per_env_phase=term_cfg.delay_per_env_phase, + ) + + if term_cfg.history_length > 0: + group_entry_history_buffer[term_name] = CircularBuffer( + max_len=term_cfg.history_length, + batch_size=self._env.num_envs, + device=self._env.device, + ) + old_dims = list(obs_dims) + old_dims.insert(1, term_cfg.history_length) + obs_dims = tuple(old_dims) + if term_cfg.flatten_history_dim: + obs_dims = (obs_dims[0], int(np.prod(obs_dims[1:]))) + + self._group_obs_term_dim[group_name].append(obs_dims[1:]) + self._group_obs_term_delay_buffer[group_name] = group_entry_delay_buffer + self._group_obs_term_history_buffer[group_name] = group_entry_history_buffer diff --git a/mjlab/src/mjlab/managers/reward_manager.py b/mjlab/src/mjlab/managers/reward_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..6afb5c7b61a4b1639d58605fcda6535bf5a5d243 --- /dev/null +++ b/mjlab/src/mjlab/managers/reward_manager.py @@ -0,0 +1,153 @@ +"""Reward manager for computing reward signals.""" + +from __future__ import annotations + +from copy import deepcopy +from dataclasses import dataclass +from typing import TYPE_CHECKING, Any + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBaseCfg + +if TYPE_CHECKING: + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv + + +@dataclass(kw_only=True) +class RewardTermCfg(ManagerTermBaseCfg): + """Configuration for a reward term.""" + + func: Any + """The callable that computes this reward term's value.""" + + weight: float + """Weight multiplier for this reward term.""" + + +class RewardManager(ManagerBase): + """Manages reward computation by aggregating weighted reward terms. + + Reward Scaling Behavior: + By default, rewards are scaled by the environment step duration (dt). This + normalizes cumulative episodic rewards across different simulation frequencies. + The scaling can be disabled via the ``scale_by_dt`` parameter. + + When ``scale_by_dt=True`` (default): + - ``reward_buf`` (returned by ``compute()``) = raw_value * weight * dt + - ``_episode_sums`` (cumulative rewards) are scaled by dt + - ``Episode_Reward/*`` logged metrics are scaled by dt + + When ``scale_by_dt=False``: + - ``reward_buf`` = raw_value * weight (no dt scaling) + + Regardless of the scaling setting: + - ``_step_reward`` (via ``get_active_iterable_terms()``) always contains + the unscaled reward rate (raw_value * weight) + """ + + _env: ManagerBasedRlEnv + + def __init__( + self, + cfg: dict[str, RewardTermCfg], + env: ManagerBasedRlEnv, + *, + scale_by_dt: bool = True, + ): + self._term_names: list[str] = list() + self._term_cfgs: list[RewardTermCfg] = list() + self._class_term_cfgs: list[RewardTermCfg] = list() + self._scale_by_dt = scale_by_dt + + self.cfg = deepcopy(cfg) + super().__init__(env=env) + self._episode_sums = dict() + for term_name in self._term_names: + self._episode_sums[term_name] = torch.zeros( + self.num_envs, dtype=torch.float, device=self.device + ) + self._reward_buf = torch.zeros(self.num_envs, dtype=torch.float, device=self.device) + self._step_reward = torch.zeros( + (self.num_envs, len(self._term_names)), dtype=torch.float, device=self.device + ) + + def __str__(self) -> str: + msg = f" contains {len(self._term_names)} active terms.\n" + table = PrettyTable() + table.title = "Active Reward Terms" + table.field_names = ["Index", "Name", "Weight"] + table.align["Name"] = "l" + table.align["Weight"] = "r" + for index, (name, term_cfg) in enumerate( + zip(self._term_names, self._term_cfgs, strict=False) + ): + table.add_row([index, name, term_cfg.weight]) + msg += table.get_string() + msg += "\n" + return msg + + # Properties. + + @property + def active_terms(self) -> list[str]: + return self._term_names + + # Methods. + + def reset( + self, env_ids: torch.Tensor | slice | None = None + ) -> dict[str, torch.Tensor]: + if env_ids is None: + env_ids = slice(None) + extras = {} + for key in self._episode_sums.keys(): + episodic_sum_avg = torch.mean(self._episode_sums[key][env_ids]) + extras["Episode_Reward/" + key] = ( + episodic_sum_avg / self._env.max_episode_length_s + ) + self._episode_sums[key][env_ids] = 0.0 + for term_cfg in self._class_term_cfgs: + term_cfg.func.reset(env_ids=env_ids) + return extras + + def compute(self, dt: float) -> torch.Tensor: + self._reward_buf[:] = 0.0 + scale = dt if self._scale_by_dt else 1.0 + for term_idx, (name, term_cfg) in enumerate( + zip(self._term_names, self._term_cfgs, strict=False) + ): + if term_cfg.weight == 0.0: + self._step_reward[:, term_idx] = 0.0 + continue + value = term_cfg.func(self._env, **term_cfg.params) * term_cfg.weight * scale + # NaN/Inf can occur from corrupted physics state; zero them to avoid policy crash. + value = torch.nan_to_num(value, nan=0.0, posinf=0.0, neginf=0.0) + self._reward_buf += value + self._episode_sums[name] += value + self._step_reward[:, term_idx] = value / scale + return self._reward_buf + + def get_active_iterable_terms(self, env_idx): + terms = [] + for idx, name in enumerate(self._term_names): + terms.append((name, [self._step_reward[env_idx, idx].cpu().item()])) + return terms + + def get_term_cfg(self, term_name: str) -> RewardTermCfg: + if term_name not in self._term_names: + raise ValueError(f"Term '{term_name}' not found in active terms.") + return self._term_cfgs[self._term_names.index(term_name)] + + def _prepare_terms(self): + for term_name, term_cfg in self.cfg.items(): + term_cfg: RewardTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + self._resolve_common_term_cfg(term_name, term_cfg) + self._term_names.append(term_name) + self._term_cfgs.append(term_cfg) + if hasattr(term_cfg.func, "reset") and callable(term_cfg.func.reset): + self._class_term_cfgs.append(term_cfg) diff --git a/mjlab/src/mjlab/managers/scene_entity_config.py b/mjlab/src/mjlab/managers/scene_entity_config.py new file mode 100644 index 0000000000000000000000000000000000000000..7b3e661794e8b894ff880d78bc85570e0ff1f0ab --- /dev/null +++ b/mjlab/src/mjlab/managers/scene_entity_config.py @@ -0,0 +1,190 @@ +"""Configuration for scene entities used by manager terms.""" + +from dataclasses import dataclass, field +from typing import NamedTuple + +from mjlab.entity import Entity +from mjlab.scene import Scene + + +class _FieldConfig(NamedTuple): + """Configuration for a resolvable entity field.""" + + names_attr: str + ids_attr: str + find_method: str + num_attr: str + kind_label: str + + +_FIELD_CONFIGS = [ + _FieldConfig("joint_names", "joint_ids", "find_joints", "num_joints", "joint"), + _FieldConfig("body_names", "body_ids", "find_bodies", "num_bodies", "body"), + _FieldConfig("geom_names", "geom_ids", "find_geoms", "num_geoms", "geom"), + _FieldConfig("site_names", "site_ids", "find_sites", "num_sites", "site"), + _FieldConfig( + "actuator_names", "actuator_ids", "find_actuators", "num_actuators", "actuator" + ), +] + + +@dataclass +class SceneEntityCfg: + """Configuration for a scene entity that is used by the manager's term. + + This configuration allows flexible specification of entity components either by name + or by ID. During resolution, it ensures consistency between names and IDs, and can + optimize to slice(None) when all components are selected. + """ + + name: str + """The name of the entity in the scene.""" + + joint_names: str | tuple[str, ...] | None = None + """Names of joints to include. Can be a single string or tuple.""" + + joint_ids: list[int] | slice = field(default_factory=lambda: slice(None)) + """IDs of joints to include. Can be a list or slice.""" + + body_names: str | tuple[str, ...] | None = None + """Names of bodies to include. Can be a single string or tuple.""" + + body_ids: list[int] | slice = field(default_factory=lambda: slice(None)) + """IDs of bodies to include. Can be a list or slice.""" + + geom_names: str | tuple[str, ...] | None = None + """Names of geometries to include. Can be a single string or tuple.""" + + geom_ids: list[int] | slice = field(default_factory=lambda: slice(None)) + """IDs of geometries to include. Can be a list or slice.""" + + site_names: str | tuple[str, ...] | None = None + """Names of sites to include. Can be a single string or tuple.""" + + site_ids: list[int] | slice = field(default_factory=lambda: slice(None)) + """IDs of sites to include. Can be a list or slice.""" + + actuator_names: str | list[str] | None = None + """Names of actuators to include. Can be a single string or list.""" + + actuator_ids: list[int] | slice = field(default_factory=lambda: slice(None)) + """IDs of actuators to include. Can be a list or slice.""" + + preserve_order: bool = False + """If True, maintains the order of components as specified.""" + + def resolve(self, scene: Scene) -> None: + """Resolve names and IDs for all configured fields. + + This method ensures consistency between names and IDs for each field type. + It handles three cases: + 1. Both names and IDs provided: Validates they match + 2. Only names provided: Computes IDs (optimizes to slice(None) if all selected) + 3. Only IDs provided: Computes names + + Args: + scene: The scene containing the entity to resolve against. + + Raises: + ValueError: If provided names and IDs are inconsistent. + KeyError: If the entity name is not found in the scene. + """ + entity = scene[self.name] + + for config in _FIELD_CONFIGS: + self._resolve_field(entity, config) + + def _resolve_field(self, entity: Entity, config: _FieldConfig) -> None: + """Resolve a single field's names and IDs. + + Args: + entity: The entity to resolve against. + config: Field configuration specifying attribute names and methods. + """ + names = getattr(self, config.names_attr) + ids = getattr(self, config.ids_attr) + + # Early return if nothing to resolve. + if names is None and not isinstance(ids, list): + return + + # Get entity metadata. + entity_all_names = getattr(entity, config.names_attr) + entity_count = getattr(entity, config.num_attr) + find_method = getattr(entity, config.find_method) + + # Normalize single values to lists for uniform processing. + names = self._normalize_to_list(names) + if names is not None: + setattr(self, config.names_attr, names) + + if isinstance(ids, (int, list)): + ids = self._normalize_to_list(ids) + setattr(self, config.ids_attr, ids) + + # Handle three resolution cases. + if names is not None and isinstance(ids, list): + self._validate_consistency( + names, ids, entity_all_names, find_method, config.kind_label + ) + elif names is not None: + self._resolve_names_to_ids( + names, entity_all_names, entity_count, find_method, config.ids_attr + ) + elif isinstance(ids, list): + self._resolve_ids_to_names(ids, entity_all_names, config.names_attr) + + def _normalize_to_list(self, value: str | int | list | None) -> list | None: + """Convert single values to lists for uniform processing.""" + if value is None: + return None + if isinstance(value, (str, int)): + return [value] + return value + + def _validate_consistency( + self, + names: list[str], + ids: list[int], + entity_all_names: list[str], + find_method, + kind_label: str, + ) -> None: + """Validate that provided names and IDs are consistent. + + Raises: + ValueError: If names and IDs don't match. + """ + found_ids, _ = find_method(names, preserve_order=self.preserve_order) + computed_names = [entity_all_names[i] for i in ids] + + if found_ids != ids or computed_names != names: + raise ValueError( + f"Inconsistent {kind_label} names and indices. " + f"Names {names} resolved to indices {found_ids}, " + f"but indices {ids} (mapping to names {computed_names}) were provided." + ) + + def _resolve_names_to_ids( + self, + names: list[str], + entity_all_names: list[str], + entity_count: int, + find_method, + ids_attr: str, + ) -> None: + """Resolve names to IDs, optimizing to slice(None) when all are selected.""" + found_ids, _ = find_method(names, preserve_order=self.preserve_order) + + # Optimize to slice(None) if all components are selected in order. + if len(found_ids) == entity_count and names == entity_all_names: + setattr(self, ids_attr, slice(None)) + else: + setattr(self, ids_attr, found_ids) + + def _resolve_ids_to_names( + self, ids: list[int], entity_all_names: list[str], names_attr: str + ) -> None: + """Resolve IDs to their corresponding names.""" + resolved_names = [entity_all_names[i] for i in ids] + setattr(self, names_attr, resolved_names) diff --git a/mjlab/src/mjlab/managers/termination_manager.py b/mjlab/src/mjlab/managers/termination_manager.py new file mode 100644 index 0000000000000000000000000000000000000000..d318086094b7744cbb18990e9ce6c9b972af42a2 --- /dev/null +++ b/mjlab/src/mjlab/managers/termination_manager.py @@ -0,0 +1,140 @@ +"""Termination manager for computing done signals.""" + +from __future__ import annotations + +from copy import deepcopy +from dataclasses import dataclass +from typing import TYPE_CHECKING, Sequence + +import torch +from prettytable import PrettyTable + +from mjlab.managers.manager_base import ManagerBase, ManagerTermBaseCfg + +if TYPE_CHECKING: + from mjlab.envs.manager_based_rl_env import ManagerBasedRlEnv + + +@dataclass +class TerminationTermCfg(ManagerTermBaseCfg): + """Configuration for a termination term.""" + + time_out: bool = False + """Whether the term contributes towards episodic timeouts.""" + + +class TerminationManager(ManagerBase): + """Manages termination conditions for the environment. + + The termination manager aggregates multiple termination terms to compute + episode done signals. Terms can be either truncations (time-based) or + terminations (failure conditions). + """ + + _env: ManagerBasedRlEnv + + def __init__(self, cfg: dict[str, TerminationTermCfg], env: ManagerBasedRlEnv): + self._term_names: list[str] = list() + self._term_cfgs: list[TerminationTermCfg] = list() + self._class_term_cfgs: list[TerminationTermCfg] = list() + + self.cfg = deepcopy(cfg) + super().__init__(env) + + self._term_dones = dict() + for term_name in self._term_names: + self._term_dones[term_name] = torch.zeros( + self.num_envs, device=self.device, dtype=torch.bool + ) + self._truncated_buf = torch.zeros( + self.num_envs, device=self.device, dtype=torch.bool + ) + self._terminated_buf = torch.zeros_like(self._truncated_buf) + + def __str__(self) -> str: + msg = f" contains {len(self._term_names)} active terms.\n" + table = PrettyTable() + table.title = "Active Termination Terms" + table.field_names = ["Index", "Name", "Time Out"] + table.align["Name"] = "l" + for index, (name, term_cfg) in enumerate( + zip(self._term_names, self._term_cfgs, strict=False) + ): + table.add_row([index, name, term_cfg.time_out]) + msg += table.get_string() + msg += "\n" + return msg + + # Properties. + + @property + def active_terms(self) -> list[str]: + return self._term_names + + @property + def dones(self) -> torch.Tensor: + return self._truncated_buf | self._terminated_buf + + @property + def time_outs(self) -> torch.Tensor: + return self._truncated_buf + + @property + def terminated(self) -> torch.Tensor: + return self._terminated_buf + + # Methods. + + def reset( + self, env_ids: torch.Tensor | slice | None = None + ) -> dict[str, torch.Tensor]: + if env_ids is None: + env_ids = slice(None) + extras = {} + for key in self._term_dones.keys(): + extras["Episode_Termination/" + key] = torch.count_nonzero( + self._term_dones[key][env_ids] + ).item() + for term_cfg in self._class_term_cfgs: + term_cfg.func.reset(env_ids=env_ids) + return extras + + def compute(self) -> torch.Tensor: + self._truncated_buf[:] = False + self._terminated_buf[:] = False + for name, term_cfg in zip(self._term_names, self._term_cfgs, strict=False): + value = term_cfg.func(self._env, **term_cfg.params) + if term_cfg.time_out: + self._truncated_buf |= value + else: + self._terminated_buf |= value + self._term_dones[name][:] = value + return self._truncated_buf | self._terminated_buf + + def get_term(self, name: str) -> torch.Tensor: + return self._term_dones[name] + + def get_term_cfg(self, term_name: str) -> TerminationTermCfg: + if term_name not in self._term_names: + raise ValueError(f"Term '{term_name}' not found in active terms.") + return self._term_cfgs[self._term_names.index(term_name)] + + def get_active_iterable_terms( + self, env_idx: int + ) -> Sequence[tuple[str, Sequence[float]]]: + terms = [] + for key in self._term_dones.keys(): + terms.append((key, [self._term_dones[key][env_idx].float().cpu().item()])) + return terms + + def _prepare_terms(self): + for term_name, term_cfg in self.cfg.items(): + term_cfg: TerminationTermCfg | None + if term_cfg is None: + print(f"term: {term_name} set to None, skipping...") + continue + self._resolve_common_term_cfg(term_name, term_cfg) + self._term_names.append(term_name) + self._term_cfgs.append(term_cfg) + if hasattr(term_cfg.func, "reset") and callable(term_cfg.func.reset): + self._class_term_cfgs.append(term_cfg) diff --git a/mjlab/src/mjlab/py.typed b/mjlab/src/mjlab/py.typed new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/mjlab/src/mjlab/rl/__init__.py b/mjlab/src/mjlab/rl/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e3d0de1893a565e74fcb2346474b84a4c6400e95 --- /dev/null +++ b/mjlab/src/mjlab/rl/__init__.py @@ -0,0 +1,6 @@ +from mjlab.rl.config import RslRlBaseRunnerCfg as RslRlBaseRunnerCfg +from mjlab.rl.config import RslRlModelCfg as RslRlModelCfg +from mjlab.rl.config import RslRlOnPolicyRunnerCfg as RslRlOnPolicyRunnerCfg +from mjlab.rl.config import RslRlPpoAlgorithmCfg as RslRlPpoAlgorithmCfg +from mjlab.rl.runner import MjlabOnPolicyRunner as MjlabOnPolicyRunner +from mjlab.rl.vecenv_wrapper import RslRlVecEnvWrapper as RslRlVecEnvWrapper diff --git a/mjlab/src/mjlab/rl/config.py b/mjlab/src/mjlab/rl/config.py new file mode 100644 index 0000000000000000000000000000000000000000..7b1d5f64cc921dc908f26b56dabea2779a74251e --- /dev/null +++ b/mjlab/src/mjlab/rl/config.py @@ -0,0 +1,128 @@ +"""RSL-RL configuration.""" + +from dataclasses import dataclass, field +from typing import Any, Literal, Tuple + + +@dataclass +class RslRlModelCfg: + """Config for a single neural network model (Actor or Critic).""" + + hidden_dims: Tuple[int, ...] = (128, 128, 128) + """The hidden dimensions of the network.""" + activation: str = "elu" + """The activation function.""" + obs_normalization: bool = False + """Whether to normalize the observations. Default is False.""" + init_noise_std: float = 1.0 + """The initial noise standard deviation.""" + noise_std_type: Literal["scalar", "log"] = "scalar" + """The type of noise standard deviation.""" + stochastic: bool = False + """Whether the model output is stochastic.""" + cnn_cfg: dict[str, Any] | None = None + """CNN encoder config. When set, class_name should be "CNNModel". + + Passed to ``rsl_rl.modules.CNN``. Common keys: output_channels, + kernel_size, stride, padding, activation, global_pool, max_pool. + """ + class_name: str = "MLPModel" + """Model class name resolved by RSL-RL (MLPModel or CNNModel).""" + + +@dataclass +class RslRlPpoAlgorithmCfg: + """Config for the PPO algorithm.""" + + num_learning_epochs: int = 5 + """The number of learning epochs per update.""" + num_mini_batches: int = 4 + """The number of mini-batches per update. + mini batch size = num_envs * num_steps / num_mini_batches + """ + learning_rate: float = 1e-3 + """The learning rate.""" + schedule: Literal["adaptive", "fixed"] = "adaptive" + """The learning rate schedule.""" + gamma: float = 0.99 + """The discount factor.""" + lam: float = 0.95 + """The lambda parameter for Generalized Advantage Estimation (GAE).""" + entropy_coef: float = 0.005 + """The coefficient for the entropy loss.""" + desired_kl: float = 0.01 + """The desired KL divergence between the new and old policies.""" + max_grad_norm: float = 1.0 + """The maximum gradient norm for the policy.""" + value_loss_coef: float = 1.0 + """The coefficient for the value loss.""" + use_clipped_value_loss: bool = True + """Whether to use clipped value loss.""" + clip_param: float = 0.2 + """The clipping parameter for the policy.""" + normalize_advantage_per_mini_batch: bool = False + """Whether to normalize the advantage per mini-batch. Default is False. If True, the + advantage is normalized over the mini-batches only. Otherwise, the advantage is + normalized over the entire collected trajectories. + """ + optimizer: Literal["adam", "adamw", "sgd", "rmsprop"] = "adam" + """The optimizer to use.""" + share_cnn_encoders: bool = False + """Share CNN encoders between actor and critic.""" + class_name: str = "PPO" + """Algorithm class name resolved by RSL-RL.""" + + +@dataclass +class RslRlBaseRunnerCfg: + seed: int = 42 + """The seed for the experiment. Default is 42.""" + num_steps_per_env: int = 24 + """The number of steps per environment update.""" + max_iterations: int = 300 + """The maximum number of iterations.""" + obs_groups: dict[str, tuple[str, ...]] = field( + default_factory=lambda: {"actor": ("actor",), "critic": ("critic",)}, + ) + save_interval: int = 50 + """The number of iterations between saves.""" + experiment_name: str = "exp1" + """Directory name used to group runs under + ``logs/rsl_rl/{experiment_name}/``.""" + run_name: str = "" + """Optional label appended to the timestamped run directory + (e.g. ``2025-01-27_14-30-00_{run_name}``). Also becomes the + display name for the run in wandb.""" + logger: Literal["wandb", "tensorboard"] = "wandb" + """The logger to use. Default is wandb.""" + wandb_project: str = "mjlab" + """The wandb project name.""" + wandb_tags: Tuple[str, ...] = () + """Tags for the wandb run. Default is empty tuple.""" + resume: bool = False + """Whether to resume the experiment. Default is False.""" + load_run: str = ".*" + """The run directory to load. Default is ".*" which means all runs. If regex + expression, the latest (alphabetical order) matching run will be loaded. + """ + load_checkpoint: str = "model_.*.pt" + """The checkpoint file to load. Default is "model_.*.pt" (all). If regex expression, + the latest (alphabetical order) matching file will be loaded. + """ + clip_actions: float | None = None + """The clipping range for action values. If None (default), no clipping is applied.""" + upload_model: bool = True + """Whether to upload model files (.pt, .onnx) to W&B on save. Set to + False to keep metric logging but avoid storage usage. Default is True.""" + + +@dataclass +class RslRlOnPolicyRunnerCfg(RslRlBaseRunnerCfg): + class_name: str = "OnPolicyRunner" + """The runner class name. Default is OnPolicyRunner.""" + actor: RslRlModelCfg = field(default_factory=lambda: RslRlModelCfg(stochastic=True)) + """The actor configuration.""" + critic: RslRlModelCfg = field(default_factory=lambda: RslRlModelCfg(stochastic=False)) + """The critic configuration.""" + algorithm: RslRlPpoAlgorithmCfg = field(default_factory=RslRlPpoAlgorithmCfg) + """The algorithm configuration.""" diff --git a/mjlab/src/mjlab/rl/exporter_utils.py b/mjlab/src/mjlab/rl/exporter_utils.py new file mode 100644 index 0000000000000000000000000000000000000000..3e82f2dbc394ba74150daceeab68b2a8941d127e --- /dev/null +++ b/mjlab/src/mjlab/rl/exporter_utils.py @@ -0,0 +1,82 @@ +"""Shared utilities for ONNX policy export across RL tasks.""" + +import onnx +import torch + +from mjlab.entity import Entity +from mjlab.envs import ManagerBasedRlEnv +from mjlab.envs.mdp.actions import JointPositionAction + + +def list_to_csv_str(arr, *, decimals: int = 3, delimiter: str = ",") -> str: + """Convert list to CSV string with specified decimal precision.""" + fmt = f"{{:.{decimals}f}}" + return delimiter.join( + fmt.format(x) + if isinstance(x, (int, float)) + else str(x) # numbers → format, strings → as-is + for x in arr + ) + + +def get_base_metadata( + env: ManagerBasedRlEnv, run_path: str +) -> dict[str, list | str | float]: + """Get base metadata common to all RL policy exports. + + Args: + env: The RL environment. + run_path: W&B run path or other identifier. + + Returns: + Dictionary of metadata fields that are common across all tasks. + """ + robot: Entity = env.scene["robot"] + joint_action = env.action_manager.get_term("joint_pos") + assert isinstance(joint_action, JointPositionAction) + # Build mapping from joint name to actuator ID for natural joint order. + # Each spec actuator controls exactly one joint (via its target field). + joint_name_to_ctrl_id = {} + for actuator in robot.spec.actuators: + joint_name = actuator.target.split("/")[-1] + joint_name_to_ctrl_id[joint_name] = actuator.id + # Get actuator IDs in natural joint order (same order as robot.joint_names). + ctrl_ids_natural = [ + joint_name_to_ctrl_id[jname] + for jname in robot.joint_names # global joint order + if jname in joint_name_to_ctrl_id # skip non-actuated joints + ] + joint_stiffness = env.sim.mj_model.actuator_gainprm[ctrl_ids_natural, 0] + joint_damping = -env.sim.mj_model.actuator_biasprm[ctrl_ids_natural, 2] + return { + "run_path": run_path, + "joint_names": list(robot.joint_names), + "joint_stiffness": joint_stiffness.tolist(), + "joint_damping": joint_damping.tolist(), + "default_joint_pos": robot.data.default_joint_pos[0].cpu().tolist(), + "command_names": list(env.command_manager.active_terms), + "observation_names": env.observation_manager.active_terms["actor"], + "action_scale": joint_action._scale[0].cpu().tolist() + if isinstance(joint_action._scale, torch.Tensor) + else joint_action._scale, + } + + +def attach_metadata_to_onnx( + onnx_path: str, metadata: dict[str, list | str | float] +) -> None: + """Attach metadata to an ONNX model file. + + Args: + onnx_path: Path to the ONNX model file. + metadata: Dictionary of metadata key-value pairs to attach. + """ + model = onnx.load(onnx_path) + + for k, v in metadata.items(): + entry = onnx.StringStringEntryProto() + entry.key = k + entry.value = list_to_csv_str(v) if isinstance(v, list) else str(v) + model.metadata_props.append(entry) + + onnx.save(model, onnx_path) diff --git a/mjlab/src/mjlab/rl/runner.py b/mjlab/src/mjlab/rl/runner.py new file mode 100644 index 0000000000000000000000000000000000000000..d94a4fbf22444170bdd17cb2882decf380e1e3a0 --- /dev/null +++ b/mjlab/src/mjlab/rl/runner.py @@ -0,0 +1,121 @@ +import os + +import torch +from rsl_rl.env import VecEnv +from rsl_rl.runners import OnPolicyRunner + +from mjlab.rl.vecenv_wrapper import RslRlVecEnvWrapper + + +class MjlabOnPolicyRunner(OnPolicyRunner): + """Base runner that persists environment state across checkpoints.""" + + env: RslRlVecEnvWrapper + + def __init__( + self, + env: VecEnv, + train_cfg: dict, + log_dir: str | None = None, + device: str = "cpu", + ) -> None: + # Strip None-valued cnn_cfg so MLPModel doesn't receive it. + for key in ("actor", "critic"): + if key in train_cfg and train_cfg[key].get("cnn_cfg") is None: + train_cfg[key].pop("cnn_cfg", None) + super().__init__(env, train_cfg, log_dir, device) + + def export_policy_to_onnx( + self, path: str, filename: str = "policy.onnx", verbose: bool = False + ) -> None: + """Export policy to ONNX format using legacy export path. + + Overrides the base implementation to set dynamo=False, avoiding warnings about + dynamic_axes being deprecated with the new TorchDynamo export path + (torch>=2.9 default). + """ + onnx_model = self.alg.get_policy().as_onnx(verbose=verbose) + onnx_model.to("cpu") + onnx_model.eval() + os.makedirs(path, exist_ok=True) + torch.onnx.export( + onnx_model, + onnx_model.get_dummy_inputs(), # type: ignore[operator] + os.path.join(path, filename), + export_params=True, + opset_version=18, + verbose=verbose, + input_names=onnx_model.input_names, # type: ignore[arg-type] + output_names=onnx_model.output_names, # type: ignore[arg-type] + dynamic_axes={}, + dynamo=False, + ) + + def save(self, path: str, infos=None) -> None: + """Save checkpoint. + + Extends the base implementation to persist the environment's + common_step_counter and to respect the ``upload_model`` config flag. + """ + env_state = {"common_step_counter": self.env.unwrapped.common_step_counter} + infos = {**(infos or {}), "env_state": env_state} + # Inline base OnPolicyRunner.save() to conditionally gate W&B upload. + saved_dict = self.alg.save() + saved_dict["iter"] = self.current_learning_iteration + saved_dict["infos"] = infos + torch.save(saved_dict, path) + if self.cfg["upload_model"]: + self.logger.save_model(path, self.current_learning_iteration) + + def load( + self, + path: str, + load_cfg: dict | None = None, + strict: bool = True, + map_location: str | None = None, + ) -> dict: + """Load checkpoint. + + Extends the base implementation to: + 1. Restore common_step_counter to preserve curricula state. + 2. Migrate legacy checkpoints (actor.* -> mlp.*, actor_obs_normalizer.* + -> obs_normalizer.*) to the current format (rsl-rl>=4.0). + """ + loaded_dict = torch.load(path, map_location=map_location, weights_only=False) + + if "model_state_dict" in loaded_dict: + print(f"Detected legacy checkpoint at {path}. Migrating to new format...") + model_state_dict = loaded_dict.pop("model_state_dict") + actor_state_dict = {} + critic_state_dict = {} + + for key, value in model_state_dict.items(): + # Migrate actor keys. + if key.startswith("actor."): + new_key = key.replace("actor.", "mlp.") + actor_state_dict[new_key] = value + elif key.startswith("actor_obs_normalizer."): + new_key = key.replace("actor_obs_normalizer.", "obs_normalizer.") + actor_state_dict[new_key] = value + elif key in ["std", "log_std"]: + actor_state_dict[key] = value + + # Migrate critic keys. + if key.startswith("critic."): + new_key = key.replace("critic.", "mlp.") + critic_state_dict[new_key] = value + elif key.startswith("critic_obs_normalizer."): + new_key = key.replace("critic_obs_normalizer.", "obs_normalizer.") + critic_state_dict[new_key] = value + + loaded_dict["actor_state_dict"] = actor_state_dict + loaded_dict["critic_state_dict"] = critic_state_dict + + load_iteration = self.alg.load(loaded_dict, load_cfg, strict) + if load_iteration: + self.current_learning_iteration = loaded_dict["iter"] + + infos = loaded_dict["infos"] + if infos and "env_state" in infos: + self.env.unwrapped.common_step_counter = infos["env_state"]["common_step_counter"] + return infos diff --git a/mjlab/src/mjlab/rl/spatial_softmax.py b/mjlab/src/mjlab/rl/spatial_softmax.py new file mode 100644 index 0000000000000000000000000000000000000000..7d3eb1498b0022b28a159df0a7d403a1e25fb553 --- /dev/null +++ b/mjlab/src/mjlab/rl/spatial_softmax.py @@ -0,0 +1,205 @@ +"""CNN with a spatial softmax layer.""" + +from __future__ import annotations + +from typing import Any + +import torch +import torch.nn as nn +from rsl_rl.models.cnn_model import CNNModel +from rsl_rl.models.mlp_model import MLPModel +from rsl_rl.modules import CNN +from tensordict import TensorDict + + +class SpatialSoftmax(nn.Module): + """Spatial soft-argmax over feature maps. + + Given input of shape ``(B, C, H, W)``, computes a softmax over each channel's spatial + locations and returns the expected (x, y) coordinates, yielding output shape + ``(B, C * 2)``. + + Args: + height: Height of the input feature maps. + width: Width of the input feature maps. + temperature: Temperature for the spatial softmax. Lower values produce sharper + distributions. + """ + + def __init__(self, height: int, width: int, temperature: float = 1.0) -> None: + super().__init__() + # Create normalised coordinate grids in [-1, 1]. + pos_x, pos_y = torch.meshgrid( + torch.linspace(-1.0, 1.0, height), + torch.linspace(-1.0, 1.0, width), + indexing="ij", + ) + # Register as buffers so they move with the module's device. + self.register_buffer("pos_x", pos_x.reshape(1, 1, -1)) + self.register_buffer("pos_y", pos_y.reshape(1, 1, -1)) + self.temperature = temperature + + def forward(self, x: torch.Tensor) -> torch.Tensor: + """Compute spatial soft-argmax. + + Args: + x: Feature maps of shape ``(B, C, H, W)``. + + Returns: + Keypoint coordinates of shape ``(B, C * 2)``. + """ + B, C, H, W = x.shape + # Flatten spatial dims: (B, C, H*W). + features = x.reshape(B, C, -1) + # Spatial softmax. + weights = torch.softmax(features / self.temperature, dim=-1) + # Expected coordinates. + pos_x: torch.Tensor = self.pos_x # type: ignore[assignment] + pos_y: torch.Tensor = self.pos_y # type: ignore[assignment] + expected_x = (weights * pos_x).sum(dim=-1) + expected_y = (weights * pos_y).sum(dim=-1) + # Interleave: (B, C*2). + return torch.stack([expected_x, expected_y], dim=-1).reshape(B, C * 2) + + +class SpatialSoftmaxCNN(nn.Module): + """CNN encoder with spatial-softmax pooling. + + Wraps ``rsl_rl.modules.CNN`` (created with ``global_pool="none"`` + and ``flatten=False``) followed by :class:`SpatialSoftmax`. Exposes the same + interface as ``CNN``: :attr:`output_dim` (int) and :attr:`output_channels` + (``None``, signalling flattened output). + + Args: + input_dim: ``(H, W)`` of the input images. + input_channels: Number of input channels. + temperature: Temperature for the spatial softmax. + **cnn_kwargs: Remaining keyword arguments forwarded to ``rsl_rl.modules.CNN``. + """ + + def __init__( + self, + input_dim: tuple[int, int], + input_channels: int, + temperature: float = 1.0, + **cnn_kwargs: Any, + ) -> None: + super().__init__() + # Override pooling/flatten — spatial softmax replaces these. + cnn_kwargs.pop("global_pool", None) + cnn_kwargs.pop("flatten", None) + self.cnn = CNN( + input_dim=input_dim, + input_channels=input_channels, + global_pool="none", + flatten=False, + **cnn_kwargs, + ) + # cnn.output_dim is (H, W) when flatten=False. + out_h, out_w = self.cnn.output_dim # type: ignore[misc] + num_channels: int = self.cnn.output_channels # type: ignore[assignment] + self.spatial_softmax = SpatialSoftmax(out_h, out_w, temperature) + self._output_dim = num_channels * 2 + + @property + def output_dim(self) -> int: + """Total flattened output dimension (C * 2).""" + return self._output_dim + + @property + def output_channels(self) -> None: + """Always ``None`` (output is flattened keypoints).""" + return None + + def forward(self, x: torch.Tensor) -> torch.Tensor: + features = self.cnn(x) + return self.spatial_softmax(features) + + +class SpatialSoftmaxCNNModel(CNNModel): + """CNN model that uses spatial-softmax pooling. + + Drop-in replacement for ``rsl_rl.models.CNNModel``. The only difference is that each + CNN encoder is wrapped with :class:`SpatialSoftmaxCNN` instead of a plain ``CNN``. + + The ``spatial_softmax_temperature`` parameter is extracted from ``cnn_cfg`` before + the remaining keys are forwarded to ``CNN``. + """ + + def __init__( + self, + obs: TensorDict, + obs_groups: dict[str, list[str]], + obs_set: str, + output_dim: int, + cnn_cfg: dict[str, dict] | dict[str, Any], + cnns: nn.ModuleDict | None = None, + hidden_dims: tuple[int] | list[int] = [256, 256, 256], # noqa: B006 + activation: str = "elu", + obs_normalization: bool = False, + stochastic: bool = False, + init_noise_std: float = 1.0, + noise_std_type: str = "scalar", + state_dependent_std: bool = False, + ) -> None: + # Separate 1D / 2D observation groups (sets self.obs_groups_2d, + # obs_dims_2d, obs_channels_2d; returns 1D info for MLPModel). + self._get_obs_dim(obs, obs_groups, obs_set) + + if cnns is not None: + if set(cnns.keys()) != set(self.obs_groups_2d): + raise ValueError( + "The 2D observations must be identical for all models sharing CNN encoders." + ) + print( + "Sharing CNN encoders between models, the CNN " + "configurations of the receiving model are ignored." + ) + _cnns = cnns + else: + # Expand a single flat config to per-group configs. + if not all(isinstance(v, dict) for v in cnn_cfg.values()): + cnn_cfg = {group: cnn_cfg for group in self.obs_groups_2d} + assert len(cnn_cfg) == len(self.obs_groups_2d), ( + "The number of CNN configurations must match the " + "number of 2D observation groups." + ) + _cnns = {} + for idx, obs_group in enumerate(self.obs_groups_2d): + group_cfg = dict(cnn_cfg[obs_group]) + group_cfg.pop("spatial_softmax", None) + temperature = group_cfg.pop("spatial_softmax_temperature", 1.0) + _cnns[obs_group] = SpatialSoftmaxCNN( + input_dim=self.obs_dims_2d[idx], + input_channels=self.obs_channels_2d[idx], + temperature=temperature, + **group_cfg, + ) + + self.cnn_latent_dim = 0 + for cnn in _cnns.values(): + if cnn.output_channels is not None: + raise ValueError( + "The output of the CNN must be flattened before passing it to the MLP." + ) + self.cnn_latent_dim += int(cnn.output_dim) # type: ignore[arg-type] + + MLPModel.__init__( + self, + obs, + obs_groups, + obs_set, + output_dim, + hidden_dims, + activation, + obs_normalization, + stochastic, + init_noise_std, + noise_std_type, + state_dependent_std, + ) + + if isinstance(_cnns, nn.ModuleDict): + self.cnns = _cnns + else: + self.cnns = nn.ModuleDict(_cnns) diff --git a/mjlab/src/mjlab/rl/vecenv_wrapper.py b/mjlab/src/mjlab/rl/vecenv_wrapper.py new file mode 100644 index 0000000000000000000000000000000000000000..a447106cb174a8b27acb338fd0402b1f817661bb --- /dev/null +++ b/mjlab/src/mjlab/rl/vecenv_wrapper.py @@ -0,0 +1,107 @@ +import torch +from rsl_rl.env import VecEnv +from tensordict import TensorDict + +from mjlab.envs import ManagerBasedRlEnv, ManagerBasedRlEnvCfg +from mjlab.utils.spaces import Space + + +class RslRlVecEnvWrapper(VecEnv): + def __init__( + self, + env: ManagerBasedRlEnv, + clip_actions: float | None = None, + ): + self.env = env + self.clip_actions = clip_actions + + self.num_envs = self.unwrapped.num_envs + self.device = torch.device(self.unwrapped.device) + self.max_episode_length = self.unwrapped.max_episode_length + self.num_actions = self.unwrapped.action_manager.total_action_dim + self._modify_action_space() + + # Reset at the start since rsl_rl does not call reset. + self.env.reset() + + @property + def cfg(self) -> ManagerBasedRlEnvCfg: + return self.unwrapped.cfg + + @property + def render_mode(self) -> str | None: + return self.env.render_mode + + @property + def observation_space(self) -> Space: + return self.env.observation_space + + @property + def action_space(self) -> Space: + return self.env.action_space + + @classmethod + def class_name(cls) -> str: + return cls.__name__ + + @property + def unwrapped(self) -> ManagerBasedRlEnv: + return self.env + + # Properties. + + @property + def episode_length_buf(self) -> torch.Tensor: + return self.unwrapped.episode_length_buf + + @episode_length_buf.setter + def episode_length_buf(self, value: torch.Tensor) -> None: # pyright: ignore[reportIncompatibleVariableOverride] + self.unwrapped.episode_length_buf = value + + def seed(self, seed: int = -1) -> int: + return self.unwrapped.seed(seed) + + def get_observations(self) -> TensorDict: + obs_dict = self.unwrapped.observation_manager.compute() + return TensorDict(obs_dict, batch_size=[self.num_envs]) + + def reset(self) -> tuple[TensorDict, dict]: + obs_dict, extras = self.env.reset() + return TensorDict(obs_dict, batch_size=[self.num_envs]), extras + + def step( + self, actions: torch.Tensor + ) -> tuple[TensorDict, torch.Tensor, torch.Tensor, dict]: + if self.clip_actions is not None: + actions = torch.clamp(actions, -self.clip_actions, self.clip_actions) + obs_dict, rew, terminated, truncated, extras = self.env.step(actions) + term_or_trunc = terminated | truncated + assert isinstance(rew, torch.Tensor) + assert isinstance(term_or_trunc, torch.Tensor) + dones = term_or_trunc.to(dtype=torch.long) + if not self.cfg.is_finite_horizon: + extras["time_outs"] = truncated + return ( + TensorDict(obs_dict, batch_size=[self.num_envs]), + rew, + dones, + extras, + ) + + def close(self) -> None: + return self.env.close() + + # Private methods. + + def _modify_action_space(self) -> None: + if self.clip_actions is None: + return + + from mjlab.utils.spaces import Box, batch_space + + self.unwrapped.single_action_space = Box( + shape=(self.num_actions,), low=-self.clip_actions, high=self.clip_actions + ) + self.unwrapped.action_space = batch_space( + self.unwrapped.single_action_space, self.num_envs + ) diff --git a/mjlab/src/mjlab/scene/__init__.py b/mjlab/src/mjlab/scene/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..3cc68e6f69c8b6210cd0e2cca7b66f631d5131d5 --- /dev/null +++ b/mjlab/src/mjlab/scene/__init__.py @@ -0,0 +1,2 @@ +from mjlab.scene.scene import Scene as Scene +from mjlab.scene.scene import SceneCfg as SceneCfg diff --git a/mjlab/src/mjlab/scene/scene.py b/mjlab/src/mjlab/scene/scene.py new file mode 100644 index 0000000000000000000000000000000000000000..d58702709f25978dc90c5776c7e616fb6bfbc3a7 --- /dev/null +++ b/mjlab/src/mjlab/scene/scene.py @@ -0,0 +1,227 @@ +from __future__ import annotations + +import warnings +from dataclasses import dataclass, field +from pathlib import Path +from typing import Any, Callable + +import mujoco +import mujoco_warp as mjwarp +import numpy as np +import torch + +from mjlab.entity import Entity, EntityCfg +from mjlab.sensor import BuiltinSensor, Sensor, SensorCfg +from mjlab.sensor.camera_sensor import CameraSensor +from mjlab.sensor.raycast_sensor import RayCastSensor +from mjlab.sensor.sensor_context import SensorContext +from mjlab.terrains.terrain_importer import TerrainImporter, TerrainImporterCfg + +_SCENE_XML = Path(__file__).parent / "scene.xml" + + +@dataclass(kw_only=True) +class SceneCfg: + num_envs: int = 1 + env_spacing: float = 2.0 + terrain: TerrainImporterCfg | None = None + entities: dict[str, EntityCfg] = field(default_factory=dict) + sensors: tuple[SensorCfg, ...] = field(default_factory=tuple) + extent: float | None = None + spec_fn: Callable[[mujoco.MjSpec], None] | None = None + + +class Scene: + def __init__(self, scene_cfg: SceneCfg, device: str) -> None: + self._cfg = scene_cfg + self._device = device + self._entities: dict[str, Entity] = {} + self._sensors: dict[str, Sensor] = {} + self._terrain: TerrainImporter | None = None + self._default_env_origins: torch.Tensor | None = None + self._sensor_context: SensorContext | None = None + + self._spec = mujoco.MjSpec.from_file(str(_SCENE_XML)) + if self._cfg.extent is not None: + self._spec.stat.extent = self._cfg.extent + self._add_terrain() + self._add_entities() + self._add_sensors() + if self._cfg.spec_fn is not None: + self._cfg.spec_fn(self._spec) + + def compile(self) -> mujoco.MjModel: + return self._spec.compile() + + def to_zip(self, path: Path) -> None: + """Export the scene to a zip file. + + Warning: The generated zip may require manual adjustment of asset paths + to be reloadable. Specifically, you may need to add assetdir="assets" + to the compiler directive in the XML. + + Args: + path: Output path for the zip file. + + TODO: Verify if this is fixed in future MuJoCo releases. + """ + with path.open("wb") as f: + mujoco.MjSpec.to_zip(self._spec, f) + + # Attributes. + + @property + def spec(self) -> mujoco.MjSpec: + return self._spec + + @property + def env_origins(self) -> torch.Tensor: + if self._terrain is not None: + assert self._terrain.env_origins is not None + return self._terrain.env_origins + assert self._default_env_origins is not None + return self._default_env_origins + + @property + def env_spacing(self) -> float: + return self._cfg.env_spacing + + @property + def entities(self) -> dict[str, Entity]: + return self._entities + + @property + def sensors(self) -> dict[str, Sensor]: + return self._sensors + + @property + def terrain(self) -> TerrainImporter | None: + return self._terrain + + @property + def num_envs(self) -> int: + return self._cfg.num_envs + + @property + def device(self) -> str: + return self._device + + def __getitem__(self, key: str) -> Any: + if key == "terrain": + if self._terrain is None: + raise KeyError("No terrain configured in this scene.") + return self._terrain + + if key in self._sensors: + return self._sensors[key] + if key in self._entities: + return self._entities[key] + + # Not found, raise helpful error. + available = list(self._entities.keys()) + list(self._sensors.keys()) + if self._terrain is not None: + available.append("terrain") + raise KeyError(f"Scene element '{key}' not found. Available: {available}") + + # Methods. + + @property + def sensor_context(self) -> SensorContext | None: + """Shared sensing resources, or None if no cameras/raycasts.""" + return self._sensor_context + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + ): + self._default_env_origins = torch.zeros( + (self._cfg.num_envs, 3), device=self._device, dtype=torch.float32 + ) + for ent in self._entities.values(): + ent.initialize(mj_model, model, data, self._device) + for sensor in self._sensors.values(): + sensor.initialize(mj_model, model, data, self._device) + + # Create SensorContext if any sensors require it. + ctx_sensors = [s for s in self._sensors.values() if s.requires_sensor_context] + if ctx_sensors: + camera_sensors = [s for s in ctx_sensors if isinstance(s, CameraSensor)] + raycast_sensors = [s for s in ctx_sensors if isinstance(s, RayCastSensor)] + self._sensor_context = SensorContext( + mj_model=mj_model, + model=model, + data=data, + camera_sensors=camera_sensors, + raycast_sensors=raycast_sensors, + device=self._device, + ) + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + for ent in self._entities.values(): + ent.reset(env_ids) + for sensor in self._sensors.values(): + sensor.reset(env_ids) + + def update(self, dt: float) -> None: + for ent in self._entities.values(): + ent.update(dt) + for sensor in self._sensors.values(): + sensor.update(dt) + + def write_data_to_sim(self) -> None: + for ent in self._entities.values(): + ent.write_data_to_sim() + + # Private methods. + + def _add_entities(self) -> None: + # Collect keyframes from each entity to merge into a single scene keyframe. + # Order matters: qpos/ctrl are concatenated in entity iteration order. + key_qpos: list[np.ndarray] = [] + key_ctrl: list[np.ndarray] = [] + for ent_name, ent_cfg in self._cfg.entities.items(): + ent = ent_cfg.build() + self._entities[ent_name] = ent + # Extract keyframe before attach (must delete before attach to avoid corruption). + if ent.spec.keys: + if len(ent.spec.keys) > 1: + warnings.warn( + f"Entity '{ent_name}' has {len(ent.spec.keys)} keyframes; only the " + "first one will be used.", + stacklevel=2, + ) + key_qpos.append(np.array(ent.spec.keys[0].qpos)) + key_ctrl.append(np.array(ent.spec.keys[0].ctrl)) + ent.spec.delete(ent.spec.keys[0]) + frame = self._spec.worldbody.add_frame() + self._spec.attach(ent.spec, prefix=f"{ent_name}/", frame=frame) + # Add merged keyframe to scene spec. + if key_qpos: + combined_qpos = np.concatenate(key_qpos) + combined_ctrl = np.concatenate(key_ctrl) + self._spec.add_key( + name="init_state", + qpos=combined_qpos.tolist(), + ctrl=combined_ctrl.tolist(), + ) + + def _add_terrain(self) -> None: + if self._cfg.terrain is None: + return + self._cfg.terrain.num_envs = self._cfg.num_envs + self._cfg.terrain.env_spacing = self._cfg.env_spacing + self._terrain = TerrainImporter(self._cfg.terrain, self._device) + frame = self._spec.worldbody.add_frame() + self._spec.attach(self._terrain.spec, prefix="", frame=frame) + + def _add_sensors(self) -> None: + for sensor_cfg in self._cfg.sensors: + sns = sensor_cfg.build() + sns.edit_spec(self._spec, self._entities) + self._sensors[sensor_cfg.name] = sns + + for sns in self._spec.sensors: + if sns.name not in self._sensors: + self._sensors[sns.name] = BuiltinSensor.from_existing(sns.name) diff --git a/mjlab/src/mjlab/scene/scene.xml b/mjlab/src/mjlab/scene/scene.xml new file mode 100644 index 0000000000000000000000000000000000000000..cb10d56587e000b33d3a08a01de4b1db7de36f52 --- /dev/null +++ b/mjlab/src/mjlab/scene/scene.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/mjlab/src/mjlab/scripts/CLAUDE.md b/mjlab/src/mjlab/scripts/CLAUDE.md new file mode 100644 index 0000000000000000000000000000000000000000..87a217da06fc1ffcd80216dacfc72669f85340be --- /dev/null +++ b/mjlab/src/mjlab/scripts/CLAUDE.md @@ -0,0 +1,11 @@ + +# Recent Activity + + + +### Feb 24, 2026 + +| ID | Time | T | Title | Read | +|----|------|---|-------|------| +| #1887 | 2:47 PM | 🔵 | Complete Motion Pipeline Documentation Traced | ~740 | + \ No newline at end of file diff --git a/mjlab/src/mjlab/scripts/csv_to_npz.py b/mjlab/src/mjlab/scripts/csv_to_npz.py new file mode 100644 index 0000000000000000000000000000000000000000..d52bb8e5adb142cc6d5b2a5f9262c760cba354c7 --- /dev/null +++ b/mjlab/src/mjlab/scripts/csv_to_npz.py @@ -0,0 +1,435 @@ +from typing import Any + +import numpy as np +import torch +import tyro +from tqdm import tqdm + +import mjlab +from mjlab.entity import Entity +from mjlab.scene import Scene +from mjlab.sim.sim import Simulation, SimulationCfg +from mjlab.tasks.tracking.config.g1.env_cfgs import unitree_g1_flat_tracking_env_cfg +from mjlab.utils.lab_api.math import ( + axis_angle_from_quat, + quat_conjugate, + quat_mul, + quat_slerp, +) +from mjlab.viewer.offscreen_renderer import OffscreenRenderer +from mjlab.viewer.viewer_config import ViewerConfig + + +class MotionLoader: + def __init__( + self, + motion_file: str, + input_fps: int, + output_fps: int, + device: torch.device | str, + line_range: tuple[int, int] | None = None, + ): + self.motion_file = motion_file + self.input_fps = input_fps + self.output_fps = output_fps + self.input_dt = 1.0 / self.input_fps + self.output_dt = 1.0 / self.output_fps + self.current_idx = 0 + self.device = device + self.line_range = line_range + self._load_motion() + self._interpolate_motion() + self._compute_velocities() + + def _load_motion(self): + """Loads the motion from the csv file.""" + if self.line_range is None: + motion = torch.from_numpy(np.loadtxt(self.motion_file, delimiter=",")) + else: + motion = torch.from_numpy( + np.loadtxt( + self.motion_file, + delimiter=",", + skiprows=self.line_range[0] - 1, + max_rows=self.line_range[1] - self.line_range[0] + 1, + ) + ) + motion = motion.to(torch.float32).to(self.device) + # motion[:, 2] -= 0.05 + self.motion_base_poss_input = motion[:, :3] + self.motion_base_rots_input = motion[:, 3:7] + self.motion_base_rots_input = self.motion_base_rots_input[ + :, [3, 0, 1, 2] + ] # convert to wxyz + self.motion_dof_poss_input = motion[:, 7:] + + self.input_frames = motion.shape[0] + self.duration = (self.input_frames - 1) * self.input_dt + + def _interpolate_motion(self): + """Interpolates the motion to the output fps.""" + times = torch.arange( + 0, self.duration, self.output_dt, device=self.device, dtype=torch.float32 + ) + self.output_frames = times.shape[0] + index_0, index_1, blend = self._compute_frame_blend(times) + self.motion_base_poss = self._lerp( + self.motion_base_poss_input[index_0], + self.motion_base_poss_input[index_1], + blend.unsqueeze(1), + ) + self.motion_base_rots = self._slerp( + self.motion_base_rots_input[index_0], + self.motion_base_rots_input[index_1], + blend, + ) + self.motion_dof_poss = self._lerp( + self.motion_dof_poss_input[index_0], + self.motion_dof_poss_input[index_1], + blend.unsqueeze(1), + ) + print( + f"Motion interpolated, input frames: {self.input_frames}, " + f"input fps: {self.input_fps}, " + f"output frames: {self.output_frames}, " + f"output fps: {self.output_fps}" + ) + + def _lerp( + self, a: torch.Tensor, b: torch.Tensor, blend: torch.Tensor + ) -> torch.Tensor: + """Linear interpolation between two tensors.""" + return a * (1 - blend) + b * blend + + def _slerp( + self, a: torch.Tensor, b: torch.Tensor, blend: torch.Tensor + ) -> torch.Tensor: + """Spherical linear interpolation between two quaternions.""" + slerped_quats = torch.zeros_like(a) + for i in range(a.shape[0]): + slerped_quats[i] = quat_slerp(a[i], b[i], float(blend[i])) + return slerped_quats + + def _compute_frame_blend( + self, times: torch.Tensor + ) -> tuple[torch.Tensor, torch.Tensor, torch.Tensor]: + """Computes the frame blend for the motion.""" + phase = times / self.duration + index_0 = (phase * (self.input_frames - 1)).floor().long() + index_1 = torch.minimum(index_0 + 1, torch.tensor(self.input_frames - 1)) + blend = phase * (self.input_frames - 1) - index_0 + return index_0, index_1, blend + + def _compute_velocities(self): + """Computes the velocities of the motion.""" + self.motion_base_lin_vels = torch.gradient( + self.motion_base_poss, spacing=self.output_dt, dim=0 + )[0] + self.motion_dof_vels = torch.gradient( + self.motion_dof_poss, spacing=self.output_dt, dim=0 + )[0] + self.motion_base_ang_vels = self._so3_derivative( + self.motion_base_rots, self.output_dt + ) + + def _so3_derivative(self, rotations: torch.Tensor, dt: float) -> torch.Tensor: + """Computes the derivative of a sequence of SO3 rotations. + + Args: + rotations: shape (B, 4). + dt: time step. + Returns: + shape (B, 3). + """ + q_prev, q_next = rotations[:-2], rotations[2:] + q_rel = quat_mul(q_next, quat_conjugate(q_prev)) # shape (B−2, 4) + + omega = axis_angle_from_quat(q_rel) / (2.0 * dt) # shape (B−2, 3) + omega = torch.cat( + [omega[:1], omega, omega[-1:]], dim=0 + ) # repeat first and last sample + return omega + + def get_next_state( + self, + ) -> tuple[ + tuple[ + torch.Tensor, + torch.Tensor, + torch.Tensor, + torch.Tensor, + torch.Tensor, + torch.Tensor, + ], + bool, + ]: + """Gets the next state of the motion.""" + state = ( + self.motion_base_poss[self.current_idx : self.current_idx + 1], + self.motion_base_rots[self.current_idx : self.current_idx + 1], + self.motion_base_lin_vels[self.current_idx : self.current_idx + 1], + self.motion_base_ang_vels[self.current_idx : self.current_idx + 1], + self.motion_dof_poss[self.current_idx : self.current_idx + 1], + self.motion_dof_vels[self.current_idx : self.current_idx + 1], + ) + self.current_idx += 1 + reset_flag = False + if self.current_idx >= self.output_frames: + self.current_idx = 0 + reset_flag = True + return state, reset_flag + + +def run_sim( + sim: Simulation, + scene: Scene, + joint_names, + input_file, + input_fps, + output_fps, + output_name, + render, + line_range, + renderer: OffscreenRenderer | None = None, +): + motion = MotionLoader( + motion_file=input_file, + input_fps=input_fps, + output_fps=output_fps, + device=sim.device, + line_range=line_range, + ) + + robot: Entity = scene["robot"] + robot_joint_indexes = robot.find_joints(joint_names, preserve_order=True)[0] + + log: dict[str, Any] = { + "fps": [output_fps], + "joint_pos": [], + "joint_vel": [], + "body_pos_w": [], + "body_quat_w": [], + "body_lin_vel_w": [], + "body_ang_vel_w": [], + } + file_saved = False + + frames = [] + scene.reset() + + print(f"\nStarting simulation with {motion.output_frames} frames...") + if render: + print("Rendering enabled - generating video frames...") + + # Create progress bar + pbar = tqdm( + total=motion.output_frames, + desc="Processing frames", + unit="frame", + ncols=100, + bar_format="{l_bar}{bar}| {n_fmt}/{total_fmt} [{elapsed}<{remaining}, {rate_fmt}]", + ) + + frame_count = 0 + while not file_saved: + ( + ( + motion_base_pos, + motion_base_rot, + motion_base_lin_vel, + motion_base_ang_vel, + motion_dof_pos, + motion_dof_vel, + ), + reset_flag, + ) = motion.get_next_state() + + root_states = robot.data.default_root_state.clone() + root_states[:, 0:3] = motion_base_pos + root_states[:, :2] += scene.env_origins[:, :2] + root_states[:, 3:7] = motion_base_rot + root_states[:, 7:10] = motion_base_lin_vel + root_states[:, 10:] = motion_base_ang_vel + robot.write_root_state_to_sim(root_states) + + joint_pos = robot.data.default_joint_pos.clone() + joint_vel = robot.data.default_joint_vel.clone() + joint_pos[:, robot_joint_indexes] = motion_dof_pos + joint_vel[:, robot_joint_indexes] = motion_dof_vel + robot.write_joint_state_to_sim(joint_pos, joint_vel) + + sim.forward() + scene.update(sim.mj_model.opt.timestep) + if render and renderer is not None: + renderer.update(sim.data) + frames.append(renderer.render()) + + if not file_saved: + log["joint_pos"].append(robot.data.joint_pos[0, :].cpu().numpy().copy()) + log["joint_vel"].append(robot.data.joint_vel[0, :].cpu().numpy().copy()) + log["body_pos_w"].append(robot.data.body_link_pos_w[0, :].cpu().numpy().copy()) + log["body_quat_w"].append(robot.data.body_link_quat_w[0, :].cpu().numpy().copy()) + log["body_lin_vel_w"].append( + robot.data.body_link_lin_vel_w[0, :].cpu().numpy().copy() + ) + log["body_ang_vel_w"].append( + robot.data.body_link_ang_vel_w[0, :].cpu().numpy().copy() + ) + + torch.testing.assert_close( + robot.data.body_link_lin_vel_w[0, 0], motion_base_lin_vel[0] + ) + torch.testing.assert_close( + robot.data.body_link_ang_vel_w[0, 0], motion_base_ang_vel[0] + ) + + frame_count += 1 + pbar.update(1) + + if frame_count % 100 == 0: # Update every 100 frames to avoid spam + elapsed_time = frame_count / output_fps + pbar.set_description(f"Processing frames (t={elapsed_time:.1f}s)") + + if reset_flag and not file_saved: + file_saved = True + pbar.close() + + print("\nStacking arrays and saving data...") + for k in ( + "joint_pos", + "joint_vel", + "body_pos_w", + "body_quat_w", + "body_lin_vel_w", + "body_ang_vel_w", + ): + log[k] = np.stack(log[k], axis=0) + + print("Saving to /tmp/motion.npz...") + np.savez("/tmp/motion.npz", **log) + + print("Uploading to Weights & Biases...") + import wandb + + COLLECTION = output_name + run = wandb.init(project="csv_to_npz", name=COLLECTION) + print(f"[INFO]: Logging motion to wandb: {COLLECTION}") + REGISTRY = "motions" + logged_artifact = run.log_artifact( + artifact_or_path="/tmp/motion.npz", name=COLLECTION, type=REGISTRY + ) + run.link_artifact( + artifact=logged_artifact, + target_path=f"wandb-registry-{REGISTRY}/{COLLECTION}", + ) + print(f"[INFO]: Motion saved to wandb registry: {REGISTRY}/{COLLECTION}") + + if render: + import mediapy as media + + print("Creating video...") + media.write_video("./motion.mp4", frames, fps=output_fps) + + print("Logging video to wandb...") + wandb.log({"motion_video": wandb.Video("./motion.mp4", format="mp4")}) + + wandb.finish() + + +def main( + input_file: str, + output_name: str, + input_fps: float = 30.0, + output_fps: float = 50.0, + device: str = "cuda:0", + render: bool = False, + line_range: tuple[int, int] | None = None, +): + """Replay motion from CSV file and output to npz file. + + Args: + input_file: Path to the input CSV file. + output_name: Path to the output npz file. + input_fps: Frame rate of the CSV file. + output_fps: Desired output frame rate. + device: Device to use. + render: Whether to render the simulation and save a video. + line_range: Range of lines to process from the CSV file. + """ + if device.startswith("cuda") and not torch.cuda.is_available(): + print("[WARNING]: CUDA is not available. Falling back to CPU. This may be slow.") + device = "cpu" + + sim_cfg = SimulationCfg() + sim_cfg.mujoco.timestep = 1.0 / output_fps + + scene = Scene(unitree_g1_flat_tracking_env_cfg().scene, device=device) + model = scene.compile() + + sim = Simulation(num_envs=1, cfg=sim_cfg, model=model, device=device) + + scene.initialize(sim.mj_model, sim.model, sim.data) + + renderer = None + if render: + viewer_cfg = ViewerConfig( + height=480, + width=640, + origin_type=ViewerConfig.OriginType.ASSET_ROOT, + distance=2.0, + elevation=-5.0, + azimuth=20, + ) + renderer = OffscreenRenderer( + model=sim.mj_model, + cfg=viewer_cfg, + scene=scene, + ) + renderer.initialize() + + run_sim( + sim=sim, + scene=scene, + joint_names=[ + "left_hip_pitch_joint", + "left_hip_roll_joint", + "left_hip_yaw_joint", + "left_knee_joint", + "left_ankle_pitch_joint", + "left_ankle_roll_joint", + "right_hip_pitch_joint", + "right_hip_roll_joint", + "right_hip_yaw_joint", + "right_knee_joint", + "right_ankle_pitch_joint", + "right_ankle_roll_joint", + "waist_yaw_joint", + "waist_roll_joint", + "waist_pitch_joint", + "left_shoulder_pitch_joint", + "left_shoulder_roll_joint", + "left_shoulder_yaw_joint", + "left_elbow_joint", + "left_wrist_roll_joint", + "left_wrist_pitch_joint", + "left_wrist_yaw_joint", + "right_shoulder_pitch_joint", + "right_shoulder_roll_joint", + "right_shoulder_yaw_joint", + "right_elbow_joint", + "right_wrist_roll_joint", + "right_wrist_pitch_joint", + "right_wrist_yaw_joint", + ], + input_fps=input_fps, + input_file=input_file, + output_fps=output_fps, + output_name=output_name, + render=render, + line_range=line_range, + renderer=renderer, + ) + + +if __name__ == "__main__": + tyro.cli(main, config=mjlab.TYRO_FLAGS) diff --git a/mjlab/src/mjlab/scripts/demo.py b/mjlab/src/mjlab/scripts/demo.py new file mode 100644 index 0000000000000000000000000000000000000000..b0c19ae2f5ad177f223ecf52a5dae165e399be67 --- /dev/null +++ b/mjlab/src/mjlab/scripts/demo.py @@ -0,0 +1,41 @@ +"""Script to run a tracking demo with a pretrained policy. + +This demo downloads a pretrained checkpoint and motion file from cloud storage +and launches an interactive viewer with a humanoid robot performing a cartwheel. +""" + +import tyro + +import mjlab +from mjlab.scripts.gcs import ensure_default_checkpoint, ensure_default_motion +from mjlab.scripts.play import PlayConfig, run_play + + +def main() -> None: + """Run demo with pretrained tracking policy.""" + print("🎮 Setting up mjlab demo with pretrained tracking policy...") + + try: + checkpoint_path = ensure_default_checkpoint() + motion_path = ensure_default_motion() + except RuntimeError as e: + print(f"❌ Failed to download demo assets: {e}") + print("Please check your internet connection and try again.") + return + + args = tyro.cli( + PlayConfig, + default=PlayConfig( + checkpoint_file=checkpoint_path, + motion_file=motion_path, + num_envs=8, + viewer="viser", + _demo_mode=True, + ), + config=mjlab.TYRO_FLAGS, + ) + run_play("Mjlab-Tracking-Flat-Unitree-G1", args) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/scripts/gcs.py b/mjlab/src/mjlab/scripts/gcs.py new file mode 100644 index 0000000000000000000000000000000000000000..109d250a24e3f81d92b8cbdb306e2d7a3124fe4e --- /dev/null +++ b/mjlab/src/mjlab/scripts/gcs.py @@ -0,0 +1,107 @@ +import hashlib +import tempfile +from pathlib import Path +from typing import TypedDict + +import requests +from tqdm import tqdm + +CACHE_DIR = Path(tempfile.gettempdir()) / "mjlab_cache" + + +class AssetInfo(TypedDict): + url: str + sha256: str + path: Path + + +ASSETS: dict[str, AssetInfo] = { + "demo_ckpt.pt": { + "url": "https://storage.googleapis.com/mjlab_beta/model_49999.pt", + "sha256": "f1bc404f5165b833a3933ac98ff223450392b78df3eb76b0c36cd1360ff22319", + "path": CACHE_DIR / "demo_ckpt.pt", + }, + "demo_motion.npz": { + "url": "https://storage.googleapis.com/mjlab_beta/lafan_dance1_subject1.npz", + "sha256": "f08d15d4b5bb605e17b6928ccdb44ae6ce7bf2038111e8b145f12a176cd096d4", + "path": CACHE_DIR / "lafan1_dance1_subject1_demo_motion.npz", + }, +} + + +def download_with_progress(url: str, path: Path) -> None: + """Download file with progress bar.""" + response = requests.get(url, stream=True) + response.raise_for_status() + + total_size = int(response.headers.get("content-length", 0)) + + with ( + open(path, "wb") as f, + tqdm( + desc=path.name, + total=total_size, + unit="B", + unit_scale=True, + unit_divisor=1024, + ) as pbar, + ): + for chunk in response.iter_content(chunk_size=8192): + size = f.write(chunk) + pbar.update(size) + + +def verify_file_hash(path: Path, expected_hash: str) -> bool: + """Verify file integrity using SHA256.""" + if not path.exists(): + return False + + sha256_hash = hashlib.sha256() + with open(path, "rb") as f: + for chunk in iter(lambda: f.read(4096), b""): + sha256_hash.update(chunk) + + return sha256_hash.hexdigest() == expected_hash + + +def ensure_asset_downloaded(asset_name: str, force_download: bool = False) -> Path: + """Download and verify an asset if needed.""" + if asset_name not in ASSETS: + raise ValueError(f"Unknown asset: {asset_name}") + + asset_info = ASSETS[asset_name] + local_path = Path(asset_info["path"]) + + if not force_download and verify_file_hash(local_path, asset_info["sha256"]): + print(f"✓ {asset_name} already cached at {local_path}") + return local_path + + print(f"📥 Downloading {asset_name}...") + local_path.parent.mkdir(parents=True, exist_ok=True) + + try: + download_with_progress(asset_info["url"], local_path) + + if not verify_file_hash(local_path, asset_info["sha256"]): + local_path.unlink() # Delete corrupted file + raise RuntimeError(f"Downloaded {asset_name} failed hash verification") + + print(f"✅ {asset_name} cached at {local_path}") + return local_path + + except Exception as e: + if local_path.exists(): + local_path.unlink() + raise RuntimeError(f"Failed to download {asset_name}: {e}") from e + + +def ensure_default_checkpoint() -> str: + """Ensure default checkpoint is available and return its absolute path.""" + checkpoint_path = ensure_asset_downloaded("demo_ckpt.pt") + return str(checkpoint_path.resolve()) + + +def ensure_default_motion() -> str: + """Ensure default motion file is available and return its absolute path.""" + motion_path = ensure_asset_downloaded("demo_motion.npz") + return str(motion_path.resolve()) diff --git a/mjlab/src/mjlab/scripts/list_envs.py b/mjlab/src/mjlab/scripts/list_envs.py new file mode 100644 index 0000000000000000000000000000000000000000..fae4e9464644f96ef21e3e9895e6b9db102d11b3 --- /dev/null +++ b/mjlab/src/mjlab/scripts/list_envs.py @@ -0,0 +1,48 @@ +"""Script to list mjlab environments.""" + +import tyro +from prettytable import PrettyTable + +import mjlab +import mjlab.tasks # noqa: F401 +from mjlab.tasks.registry import list_tasks + + +def list_environments(keyword: str | None = None): + """List all registered environments. + + Args: + keyword: Optional filter to only show environments containing this keyword. + """ + table = PrettyTable(["#", "Task ID"]) + table.title = "Available Environments in mjlab" + table.align["Task ID"] = "l" + + all_tasks = list_tasks() + idx = 0 + for task_id in all_tasks: + try: + # Optionally filter by keyword. + if keyword and keyword.lower() not in task_id.lower(): + continue + + table.add_row([idx + 1, task_id]) + idx += 1 + except Exception: + continue + + print(table) + if idx == 0: + msg = "[INFO] No tasks matched" + if keyword: + msg += f" keyword '{keyword}'" + print(msg) + return idx + + +def main(): + return tyro.cli(list_environments, config=mjlab.TYRO_FLAGS) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/scripts/nan_viz.py b/mjlab/src/mjlab/scripts/nan_viz.py new file mode 100644 index 0000000000000000000000000000000000000000..d0b1909fcf49a742a50bf4746a3c90ec622e78b4 --- /dev/null +++ b/mjlab/src/mjlab/scripts/nan_viz.py @@ -0,0 +1,176 @@ +"""Visualize NaN dump states in Viser. + +Loads a NaN dump (npz + mjb) and provides a slider to scrub through captured +states frame by frame. + +Example: + uv run viz-nan /tmp/mjlab/nan_dumps/nan_dump_20251014_095857.npz +""" + +from __future__ import annotations + +from pathlib import Path + +import mujoco +import numpy as np +import tyro +import viser + +import mjlab +from mjlab.viewer.viser import ViserMujocoScene + + +class NanDumpViewer: + """Viewer for NaN dump files.""" + + def __init__(self, dump_path: str | Path): + self.dump_path = Path(dump_path) + self.output_dir = self.dump_path.parent + + print(f"Loading NaN dump from: {self.dump_path}") + self.dump = np.load(self.dump_path, allow_pickle=True) + self.metadata = self.dump["_metadata"].item() + + model_file = self.output_dir / self.metadata["model_file"] + print(f"Loading model from: {model_file}") + self.model = mujoco.MjModel.from_binary_path(str(model_file)) + self.data = mujoco.MjData(self.model) + + self.state_keys = sorted( + [k for k in self.dump.keys() if k.startswith("states_step_")], + key=lambda x: int(x.split("_")[-1]), + ) + self.num_steps = len(self.state_keys) + self.num_envs_dumped = self.metadata["num_envs_dumped"] + self.dumped_env_ids = self.metadata["dumped_env_ids"] + + print("\nDump info:") + print(f" Total environments: {self.metadata['num_envs_total']}") + print(f" Dumped environments: {self.num_envs_dumped}") + print(f" Dumped env IDs: {self.dumped_env_ids}") + print(f" NaN detected in envs: {self.metadata['nan_env_ids']}") + print(f" Buffer size: {self.num_steps} steps") + print(f" State size: {self.metadata['state_size']}") + + self.server = viser.ViserServer(label="NaN Dump Viewer") + self.current_step = 0 + self.current_env = 0 + self.scene = ViserMujocoScene.create(self.server, self.model, num_envs=1) + + def setup(self) -> None: + """Setup the viewer GUI and scene.""" + self.info_html = self.server.gui.add_html(self._get_info_html()) + + with self.server.gui.add_folder("Playback"): + self.step_slider = self.server.gui.add_slider( + "Step", + min=0, + max=self.num_steps - 1, + step=1, + initial_value=0, + hint=f"Scrub through {self.num_steps} captured states", + ) + + @self.step_slider.on_update + def _(_) -> None: + self.current_step = int(self.step_slider.value) + self._update_state() + + if self.num_envs_dumped > 1: + self.env_slider = self.server.gui.add_slider( + "Environment", + min=0, + max=self.num_envs_dumped - 1, + step=1, + initial_value=0, + hint=f"Select environment (0-{self.num_envs_dumped - 1})", + ) + + @self.env_slider.on_update + def _(_) -> None: + self.current_env = int(self.env_slider.value) + self._update_state() + + # Add standard visualization options (hide debug viz control since no env). + self.scene.create_visualization_gui(show_debug_viz_control=False) + + # Initial state update. + self._update_state() + + def _get_info_html(self) -> str: + """Generate info HTML.""" + nan_env_ids = self.metadata["nan_env_ids"] + nan_env_str = ", ".join(str(e) for e in nan_env_ids[:10]) + if len(nan_env_ids) > 10: + nan_env_str += "..." + + step_name = self.state_keys[self.current_step] + step_num = int(step_name.split("_")[-1]) + + actual_env_id = self.dumped_env_ids[self.current_env] + is_nan_env = actual_env_id in nan_env_ids + nan_indicator = "⚠️ NaN Detected" if is_nan_env else "✓ Clean" + + return f""" +
+ Step: {step_num}
+ Environment: {actual_env_id}
+ Status: {nan_indicator}
+ NaN envs: {nan_env_str} +
+ """ + + def _update_state(self) -> None: + """Update the visualization to show the current state.""" + state_key = self.state_keys[self.current_step] + states = self.dump[state_key] + state = states[self.current_env] + + # Set state and compute derived quantities. + mujoco.mj_setState(self.model, self.data, state, mujoco.mjtState.mjSTATE_PHYSICS) + mujoco.mj_forward(self.model, self.data) + + # Update scene from single-environment MuJoCo data. + self.scene.update_from_mjdata(self.data) + + # Update info display. + self.info_html.content = self._get_info_html() + + def run(self) -> None: + """Run the viewer (blocks until server is stopped).""" + print("\nUse the sliders to scrub through states.") + print("Press Ctrl+C to exit.") + + try: + while True: + import time + + # Check if visualization settings changed and need a refresh. + if self.scene.needs_update: + self.scene.refresh_visualization() + + time.sleep(0.1) + except KeyboardInterrupt: + print("\nShutting down...") + self.server.stop() + + +def run_viewer(dump_path: tyro.conf.Positional[str]): + """View NaN dump states in Viser. + + Args: + dump_path: Path to nan_dump_TIMESTAMP.npz file. + """ + viewer = NanDumpViewer(dump_path) + viewer.setup() + viewer.run() + + +def main(): + """CLI entry point for viz-nan command.""" + + tyro.cli(run_viewer, description=__doc__, config=mjlab.TYRO_FLAGS) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/scripts/play.py b/mjlab/src/mjlab/scripts/play.py new file mode 100644 index 0000000000000000000000000000000000000000..b8cf5c50eb4beb8208f3a1e4df56aa5dc5afc903 --- /dev/null +++ b/mjlab/src/mjlab/scripts/play.py @@ -0,0 +1,242 @@ +"""Script to play RL agent with RSL-RL.""" + +import os +import sys +from dataclasses import asdict, dataclass +from pathlib import Path +from typing import Literal + +import torch +import tyro + +from mjlab.envs import ManagerBasedRlEnv +from mjlab.rl import MjlabOnPolicyRunner, RslRlVecEnvWrapper +from mjlab.tasks.registry import list_tasks, load_env_cfg, load_rl_cfg, load_runner_cls +from mjlab.tasks.tracking.mdp import MotionCommandCfg +from mjlab.utils.os import get_wandb_checkpoint_path +from mjlab.utils.torch import configure_torch_backends +from mjlab.utils.wrappers import VideoRecorder +from mjlab.viewer import NativeMujocoViewer, ViserPlayViewer + + +@dataclass(frozen=True) +class PlayConfig: + agent: Literal["zero", "random", "trained"] = "trained" + registry_name: str | None = None + wandb_run_path: str | None = None + checkpoint_file: str | None = None + motion_file: str | None = None + num_envs: int | None = None + device: str | None = None + video: bool = False + video_length: int = 200 + video_height: int | None = None + video_width: int | None = None + camera: int | str | None = None + viewer: Literal["auto", "native", "viser"] = "auto" + no_terminations: bool = False + """Disable all termination conditions (useful for viewing motions with dummy agents).""" + + # Internal flag used by demo script. + _demo_mode: tyro.conf.Suppress[bool] = False + + +def run_play(task_id: str, cfg: PlayConfig): + configure_torch_backends() + + device = cfg.device or ("cuda:0" if torch.cuda.is_available() else "cpu") + + env_cfg = load_env_cfg(task_id, play=True) + agent_cfg = load_rl_cfg(task_id) + + DUMMY_MODE = cfg.agent in {"zero", "random"} + TRAINED_MODE = not DUMMY_MODE + + # Disable terminations if requested (useful for viewing motions). + if cfg.no_terminations: + env_cfg.terminations = {} + print("[INFO]: Terminations disabled") + + # Check if this is a tracking task by checking for motion command. + is_tracking_task = "motion" in env_cfg.commands and isinstance( + env_cfg.commands["motion"], MotionCommandCfg + ) + + if is_tracking_task and cfg._demo_mode: + # Demo mode: use uniform sampling to see more diversity with num_envs > 1. + motion_cmd = env_cfg.commands["motion"] + assert isinstance(motion_cmd, MotionCommandCfg) + motion_cmd.sampling_mode = "uniform" + + if is_tracking_task: + motion_cmd = env_cfg.commands["motion"] + assert isinstance(motion_cmd, MotionCommandCfg) + + # Check for local motion file first (works for both dummy and trained modes). + if cfg.motion_file is not None and Path(cfg.motion_file).exists(): + print(f"[INFO]: Using local motion file: {cfg.motion_file}") + motion_cmd.motion_file = cfg.motion_file + elif DUMMY_MODE: + if not cfg.registry_name: + raise ValueError( + "Tracking tasks require either:\n" + " --motion-file /path/to/motion.npz (local file)\n" + " --registry-name your-org/motions/motion-name (download from WandB)" + ) + # Check if the registry name includes alias, if not, append ":latest". + registry_name = cfg.registry_name + if ":" not in registry_name: + registry_name = registry_name + ":latest" + import wandb + + api = wandb.Api() + artifact = api.artifact(registry_name) + motion_cmd.motion_file = str(Path(artifact.download()) / "motion.npz") + else: + if cfg.motion_file is not None: + print(f"[INFO]: Using motion file from CLI: {cfg.motion_file}") + motion_cmd.motion_file = cfg.motion_file + else: + import wandb + + api = wandb.Api() + if cfg.wandb_run_path is None and cfg.checkpoint_file is not None: + raise ValueError( + "Tracking tasks require `motion_file` when using `checkpoint_file`, " + "or provide `wandb_run_path` so the motion artifact can be resolved." + ) + if cfg.wandb_run_path is not None: + wandb_run = api.run(str(cfg.wandb_run_path)) + art = next( + (a for a in wandb_run.used_artifacts() if a.type == "motions"), None + ) + if art is None: + raise RuntimeError("No motion artifact found in the run.") + motion_cmd.motion_file = str(Path(art.download()) / "motion.npz") + + log_dir: Path | None = None + resume_path: Path | None = None + if TRAINED_MODE: + log_root_path = (Path("logs") / "rsl_rl" / agent_cfg.experiment_name).resolve() + if cfg.checkpoint_file is not None: + resume_path = Path(cfg.checkpoint_file) + if not resume_path.exists(): + raise FileNotFoundError(f"Checkpoint file not found: {resume_path}") + print(f"[INFO]: Loading checkpoint: {resume_path.name}") + else: + if cfg.wandb_run_path is None: + raise ValueError( + "`wandb_run_path` is required when `checkpoint_file` is not provided." + ) + resume_path, was_cached = get_wandb_checkpoint_path( + log_root_path, Path(cfg.wandb_run_path) + ) + # Extract run_id and checkpoint name from path for display. + run_id = resume_path.parent.name + checkpoint_name = resume_path.name + cached_str = "cached" if was_cached else "downloaded" + print( + f"[INFO]: Loading checkpoint: {checkpoint_name} (run: {run_id}, {cached_str})" + ) + log_dir = resume_path.parent + + if cfg.num_envs is not None: + env_cfg.scene.num_envs = cfg.num_envs + if cfg.video_height is not None: + env_cfg.viewer.height = cfg.video_height + if cfg.video_width is not None: + env_cfg.viewer.width = cfg.video_width + + render_mode = "rgb_array" if (TRAINED_MODE and cfg.video) else None + if cfg.video and DUMMY_MODE: + print( + "[WARN] Video recording with dummy agents is disabled (no checkpoint/log_dir)." + ) + env = ManagerBasedRlEnv(cfg=env_cfg, device=device, render_mode=render_mode) + + if TRAINED_MODE and cfg.video: + print("[INFO] Recording videos during play") + assert log_dir is not None # log_dir is set in TRAINED_MODE block + env = VideoRecorder( + env, + video_folder=log_dir / "videos" / "play", + step_trigger=lambda step: step == 0, + video_length=cfg.video_length, + disable_logger=True, + ) + + env = RslRlVecEnvWrapper(env, clip_actions=agent_cfg.clip_actions) + if DUMMY_MODE: + action_shape: tuple[int, ...] = env.unwrapped.action_space.shape + if cfg.agent == "zero": + + class PolicyZero: + def __call__(self, obs) -> torch.Tensor: + del obs + return torch.zeros(action_shape, device=env.unwrapped.device) + + policy = PolicyZero() + else: + + class PolicyRandom: + def __call__(self, obs) -> torch.Tensor: + del obs + return 2 * torch.rand(action_shape, device=env.unwrapped.device) - 1 + + policy = PolicyRandom() + else: + runner_cls = load_runner_cls(task_id) or MjlabOnPolicyRunner + runner = runner_cls(env, asdict(agent_cfg), device=device) + runner.load( + str(resume_path), load_cfg={"actor": True}, strict=True, map_location=device + ) + policy = runner.get_inference_policy(device=device) + + # Handle "auto" viewer selection. + if cfg.viewer == "auto": + has_display = bool(os.environ.get("DISPLAY") or os.environ.get("WAYLAND_DISPLAY")) + resolved_viewer = "native" if has_display else "viser" + del has_display + else: + resolved_viewer = cfg.viewer + + if resolved_viewer == "native": + NativeMujocoViewer(env, policy).run() + elif resolved_viewer == "viser": + ViserPlayViewer(env, policy).run() + else: + raise RuntimeError(f"Unsupported viewer backend: {resolved_viewer}") + + env.close() + + +def main(): + # Parse first argument to choose the task. + # Import tasks to populate the registry. + import mjlab.tasks # noqa: F401 + + all_tasks = list_tasks() + chosen_task, remaining_args = tyro.cli( + tyro.extras.literal_type_from_choices(all_tasks), + add_help=False, + return_unknown_args=True, + config=mjlab.TYRO_FLAGS, + ) + + # Parse the rest of the arguments + allow overriding env_cfg and agent_cfg. + agent_cfg = load_rl_cfg(chosen_task) + + args = tyro.cli( + PlayConfig, + args=remaining_args, + default=PlayConfig(), + prog=sys.argv[0] + f" {chosen_task}", + config=mjlab.TYRO_FLAGS, + ) + del remaining_args, agent_cfg + + run_play(chosen_task, args) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/scripts/train.py b/mjlab/src/mjlab/scripts/train.py new file mode 100644 index 0000000000000000000000000000000000000000..0cc9493d45436a678f4f3bfe83ade7585c91ad2f --- /dev/null +++ b/mjlab/src/mjlab/scripts/train.py @@ -0,0 +1,253 @@ +"""Script to train RL agent with RSL-RL.""" + +import logging +import os +import sys +from dataclasses import asdict, dataclass, field +from datetime import datetime +from pathlib import Path +from typing import Literal, cast + +import tyro + +from mjlab.envs import ManagerBasedRlEnv, ManagerBasedRlEnvCfg +from mjlab.rl import MjlabOnPolicyRunner, RslRlOnPolicyRunnerCfg, RslRlVecEnvWrapper +from mjlab.tasks.registry import list_tasks, load_env_cfg, load_rl_cfg, load_runner_cls +from mjlab.tasks.tracking.mdp import MotionCommandCfg +from mjlab.utils.gpu import select_gpus +from mjlab.utils.os import dump_yaml, get_checkpoint_path, get_wandb_checkpoint_path +from mjlab.utils.torch import configure_torch_backends +from mjlab.utils.wandb import add_wandb_tags +from mjlab.utils.wrappers import VideoRecorder + + +@dataclass(frozen=True) +class TrainConfig: + env: ManagerBasedRlEnvCfg + agent: RslRlOnPolicyRunnerCfg + registry_name: str | None = None + video: bool = False + video_length: int = 200 + video_interval: int = 2000 + enable_nan_guard: bool = False + torchrunx_log_dir: str | None = None + wandb_run_path: str | None = None + gpu_ids: list[int] | Literal["all"] | None = field(default_factory=lambda: [0]) + + @staticmethod + def from_task(task_id: str) -> "TrainConfig": + env_cfg = load_env_cfg(task_id) + agent_cfg = load_rl_cfg(task_id) + assert isinstance(agent_cfg, RslRlOnPolicyRunnerCfg) + return TrainConfig(env=env_cfg, agent=agent_cfg) + + +def run_train(task_id: str, cfg: TrainConfig, log_dir: Path) -> None: + cuda_visible = os.environ.get("CUDA_VISIBLE_DEVICES", "") + if cuda_visible == "": + device = "cpu" + seed = cfg.agent.seed + rank = 0 + else: + local_rank = int(os.environ.get("LOCAL_RANK", "0")) + rank = int(os.environ.get("RANK", "0")) + # Set EGL device to match the CUDA device. + os.environ["MUJOCO_EGL_DEVICE_ID"] = str(local_rank) + device = f"cuda:{local_rank}" + # Set seed to have diversity in different processes. + seed = cfg.agent.seed + local_rank + + configure_torch_backends() + + cfg.agent.seed = seed + cfg.env.seed = seed + + print(f"[INFO] Training with: device={device}, seed={seed}, rank={rank}") + + registry_name: str | None = None + + # Check if this is a tracking task by checking for motion command. + is_tracking_task = "motion" in cfg.env.commands and isinstance( + cfg.env.commands["motion"], MotionCommandCfg + ) + + if is_tracking_task: + motion_cmd = cfg.env.commands["motion"] + assert isinstance(motion_cmd, MotionCommandCfg) + + # Check if motion_file is already set (e.g., via CLI --env.commands.motion.motion-file). + if motion_cmd.motion_file and Path(motion_cmd.motion_file).exists(): + print(f"[INFO] Using local motion file: {motion_cmd.motion_file}") + elif cfg.registry_name: + # Download from WandB registry. + registry_name = cast(str, cfg.registry_name) + if ":" not in registry_name: + registry_name = registry_name + ":latest" + import wandb + + api = wandb.Api() + artifact = api.artifact(registry_name) + motion_cmd.motion_file = str(Path(artifact.download()) / "motion.npz") + else: + raise ValueError( + "For tracking tasks, provide either:\n" + " --registry-name your-org/motions/motion-name (download from WandB)\n" + " --env.commands.motion.motion-file /path/to/motion.npz (local file)" + ) + + # Enable NaN guard if requested. + if cfg.enable_nan_guard: + cfg.env.sim.nan_guard.enabled = True + print(f"[INFO] NaN guard enabled, output dir: {cfg.env.sim.nan_guard.output_dir}") + + if rank == 0: + print(f"[INFO] Logging experiment in directory: {log_dir}") + + env = ManagerBasedRlEnv( + cfg=cfg.env, device=device, render_mode="rgb_array" if cfg.video else None + ) + + log_root_path = log_dir.parent # Go up from specific run dir to experiment dir. + + resume_path: Path | None = None + if cfg.agent.resume: + if cfg.wandb_run_path is not None: + # Load checkpoint from W&B. + resume_path, was_cached = get_wandb_checkpoint_path( + log_root_path, Path(cfg.wandb_run_path) + ) + if rank == 0: + run_id = resume_path.parent.name + checkpoint_name = resume_path.name + cached_str = "cached" if was_cached else "downloaded" + print( + f"[INFO]: Loading checkpoint from W&B: {checkpoint_name} " + f"(run: {run_id}, {cached_str})" + ) + else: + # Load checkpoint from local filesystem. + resume_path = get_checkpoint_path( + log_root_path, cfg.agent.load_run, cfg.agent.load_checkpoint + ) + + # Only record videos on rank 0 to avoid multiple workers writing to the same files. + if cfg.video and rank == 0: + env = VideoRecorder( + env, + video_folder=Path(log_dir) / "videos" / "train", + step_trigger=lambda step: step % cfg.video_interval == 0, + video_length=cfg.video_length, + disable_logger=True, + ) + print("[INFO] Recording videos during training.") + + env = RslRlVecEnvWrapper(env, clip_actions=cfg.agent.clip_actions) + + agent_cfg = asdict(cfg.agent) + env_cfg = asdict(cfg.env) + + runner_cls = load_runner_cls(task_id) + if runner_cls is None: + runner_cls = MjlabOnPolicyRunner + + runner_kwargs = {} + if is_tracking_task: + runner_kwargs["registry_name"] = registry_name + + runner = runner_cls(env, agent_cfg, str(log_dir), device, **runner_kwargs) + + add_wandb_tags(cfg.agent.wandb_tags) + runner.add_git_repo_to_log(__file__) + if resume_path is not None: + print(f"[INFO]: Loading model checkpoint from: {resume_path}") + runner.load(str(resume_path)) + + # Only write config files from rank 0 to avoid race conditions. + if rank == 0: + dump_yaml(log_dir / "params" / "env.yaml", env_cfg) + dump_yaml(log_dir / "params" / "agent.yaml", agent_cfg) + + runner.learn( + num_learning_iterations=cfg.agent.max_iterations, init_at_random_ep_len=True + ) + + env.close() + + +def launch_training(task_id: str, args: TrainConfig | None = None): + args = args or TrainConfig.from_task(task_id) + + # Create log directory once before launching workers. + log_root_path = Path("logs") / "rsl_rl" / args.agent.experiment_name + log_root_path.resolve() + log_dir_name = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + if args.agent.run_name: + log_dir_name += f"_{args.agent.run_name}" + log_dir = log_root_path / log_dir_name + + # Select GPUs based on CUDA_VISIBLE_DEVICES and user specification. + selected_gpus, num_gpus = select_gpus(args.gpu_ids) + + # Set environment variables for all modes. + if selected_gpus is None: + os.environ["CUDA_VISIBLE_DEVICES"] = "" + else: + os.environ["CUDA_VISIBLE_DEVICES"] = ",".join(map(str, selected_gpus)) + os.environ["MUJOCO_GL"] = "egl" + + if num_gpus <= 1: + # CPU or single GPU: run directly without torchrunx. + run_train(task_id, args, log_dir) + else: + # Multi-GPU: use torchrunx. + import torchrunx + + # torchrunx redirects stdout to logging. + logging.basicConfig(level=logging.INFO) + + # Configure torchrunx logging directory. + # Priority: 1) existing env var, 2) user flag, 3) default to {log_dir}/torchrunx. + if "TORCHRUNX_LOG_DIR" not in os.environ: + if args.torchrunx_log_dir is not None: + # User specified a value via flag (could be "" to disable). + os.environ["TORCHRUNX_LOG_DIR"] = args.torchrunx_log_dir + else: + # Default: put logs in training directory. + os.environ["TORCHRUNX_LOG_DIR"] = str(log_dir / "torchrunx") + + print(f"[INFO] Launching training with {num_gpus} GPUs", flush=True) + torchrunx.Launcher( + hostnames=["localhost"], + workers_per_host=num_gpus, + backend=None, # Let rsl_rl handle process group initialization. + copy_env_vars=torchrunx.DEFAULT_ENV_VARS_FOR_COPY + ("MUJOCO*",), + ).run(run_train, task_id, args, log_dir) + + +def main(): + # Parse first argument to choose the task. + # Import tasks to populate the registry. + import mjlab.tasks # noqa: F401 + + all_tasks = list_tasks() + chosen_task, remaining_args = tyro.cli( + tyro.extras.literal_type_from_choices(all_tasks), + add_help=False, + return_unknown_args=True, + config=mjlab.TYRO_FLAGS, + ) + + args = tyro.cli( + TrainConfig, + args=remaining_args, + default=TrainConfig.from_task(chosen_task), + prog=sys.argv[0] + f" {chosen_task}", + config=mjlab.TYRO_FLAGS, + ) + del remaining_args + + launch_training(task_id=chosen_task, args=args) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/scripts/visualize_terrain.py b/mjlab/src/mjlab/scripts/visualize_terrain.py new file mode 100644 index 0000000000000000000000000000000000000000..0247f77f5c0d5dd4f1e5ca0da63c3abe60953241 --- /dev/null +++ b/mjlab/src/mjlab/scripts/visualize_terrain.py @@ -0,0 +1,520 @@ +"""Interactive terrain visualizer using Viser. + +Displays a 10-row grid of terrains with increasing difficulty. +Configurations and parameters are dynamically loaded from mjlab.terrains.config. + +Run with: + uv run src/mjlab/scripts/visualize_terrain.py +""" + +from __future__ import annotations + +import dataclasses +import re +import time +from typing import Any, List, TypedDict + +import mujoco +import numpy as np +import viser + +from mjlab.asset_zoo.robots import ( + get_g1_robot_cfg, + get_go1_robot_cfg, + get_yam_robot_cfg, +) +from mjlab.terrains.config import ALL_TERRAINS_CFG +from mjlab.terrains.terrain_generator import ( + TerrainGenerator, + TerrainGeneratorCfg, +) +from mjlab.viewer.viser.conversions import ( + merge_geoms, + merge_geoms_global, +) + +# Supported robots for visualization. +ROBOT_CFG_GETTERS = { + "None": None, + "Unitree Go1": get_go1_robot_cfg, + "Unitree G1": get_g1_robot_cfg, + "Yam": get_yam_robot_cfg, +} + +# Parameter range hints for sliders. +PARAM_HINTS = { + "octaves": (1, 10, 1), + "persistence": (0.0, 1.0, 0.05), + "lacunarity": (1.0, 5.0, 0.1), + "scale": (0.01, 0.5, 0.01), + "horizontal_scale": (0.001, 0.1, 0.001), + "resolution": (0.1, 2.0, 0.1), + "base_thickness_ratio": (0.1, 2.0, 0.1), + "border_width": (0.0, 2.0, 0.05), + "amplitude_range": (0.0, 1.0, 0.05), + "height_range": (0.0, 2.0, 0.05), + "num_waves": (1, 20, 1), + "num_obstacles": (1, 100, 1), + "obstacle_height_range": (0.0, 1.0, 0.05), + "obstacle_width_range": (0.1, 2.0, 0.05), + "box_width_range": (0.1, 2.0, 0.05), + "box_length_range": (0.1, 2.0, 0.05), + "slope_range": (0.0, 1.0, 0.05), + "platform_width": (0.1, 5.0, 0.1), + "step_height_range": (0.0, 0.5, 0.01), + "step_width": (0.1, 1.0, 0.05), + "grid_width": (0.1, 1.0, 0.05), + "grid_height_range": (0.0, 1.0, 0.05), + "height_merge_threshold": (0.01, 0.2, 0.01), + "max_merge_distance": (1, 10, 1), + "num_beams": (1, 64, 1), + "num_rings": (1, 32, 1), + "displacement_range": (0.0, 1.0, 0.005), + "stone_size_variation": (0.0, 1.0, 0.005), + "stone_height_variation": (0.0, 1.0, 0.005), +} + + +class _AppState(TypedDict): + preset_name: str + robot_name: str + seed: int + size: tuple[float, float] + params: dict[str, Any] + rows: int + cols: int + difficulty_range: tuple[float, float] + robot_handles: list[Any] + terrain_origins: np.ndarray | None + + +def main(): + server = viser.ViserServer() + + # Load available terrains from config. + available_presets = ALL_TERRAINS_CFG.sub_terrains + preset_names = ["All Terrains"] + list(available_presets.keys()) + + # State management. + state: _AppState = { + "preset_name": preset_names[0], + "robot_name": "None", + "seed": 42, + "size": ALL_TERRAINS_CFG.size, + "params": {}, + "rows": 10, + "cols": 1, + "difficulty_range": (0.0, 1.0), + "robot_handles": [], + "terrain_origins": None, + } + + # Handle for the terrain mesh in the scene. + terrain_handle: viser.SceneNodeHandle | None = None + + # GUI for statistics. + gui_stats_folder = server.gui.add_folder("Statistics") + with gui_stats_folder: + status_label = server.gui.add_markdown("**Status:** Ready") + polygon_count_label = server.gui.add_markdown("**Number of Polygons:** -") + + def update_robots(): + # Clear old robot handles. + for h in state["robot_handles"]: + h.remove() + state["robot_handles"] = [] + + if state["robot_name"] == "None" or state["terrain_origins"] is None: + status_label.content = "**Status:** Ready" + return + + status_label.content = f"**Status:** Spawning {state['robot_name']}..." + + # Get robot config. + robot_cfg_getter = ROBOT_CFG_GETTERS[state["robot_name"]] + if robot_cfg_getter is None: + return + robot_cfg = robot_cfg_getter() + + # Merge robot template mesh. + # We compile the robot spec standalone to get a clean local-space mesh template. + robot_spec = robot_cfg.spec_fn() + if robot_spec.worldbody.bodies: + robot_spec.worldbody.bodies[0].pos = (0, 0, 0) + + if robot_spec.keys: + robot_spec.delete(robot_spec.keys[0]) + + robot_model = robot_spec.compile() + robot_data = mujoco.MjData(robot_model) + + # Apply joint poses. + joint_pos = robot_cfg.init_state.joint_pos + if joint_pos is None: + joint_pos = {} + for pattern, val in joint_pos.items(): + if not pattern.startswith("^"): + pattern = ".*" + pattern + for j_id in range(robot_model.njnt): + name = mujoco.mj_id2name(robot_model, mujoco.mjtObj.mjOBJ_JOINT, j_id) + if re.match(pattern, name): + adr = robot_model.jnt_qposadr[j_id] + robot_data.qpos[adr] = val + + mujoco.mj_forward(robot_model, robot_data) + + # Filter for visual geoms only (group < 3). + visual_geom_ids = [ + i for i in range(robot_model.ngeom) if robot_model.geom_group[i] < 3 + ] + if not visual_geom_ids: + status_label.content = "**Status:** Error: No visual geoms for robot" + print(f"Error: No visual geoms found for {state['robot_name']}") + return + + robot_mesh = merge_geoms_global(robot_model, robot_data, visual_geom_ids) + n_verts = len(robot_mesh.vertices) + n_faces = len(robot_mesh.faces) + print(f"Robot mesh: {n_verts} vertices, {n_faces} faces.") + + # Prepare batched positions. + num_rows, num_cols = state["terrain_origins"].shape[:2] + batched_positions = [] + for row in range(num_rows): + for col in range(num_cols): + origin = state["terrain_origins"][row, col] + pos = origin + np.array(robot_cfg.init_state.pos) + batched_positions.append(pos) + + batched_positions = np.array(batched_positions) + n = len(batched_positions) + print(f"Instancing {n} robots at positions like {batched_positions[0]}") + batched_wxyzs = np.array([1.0, 0.0, 0.0, 0.0])[None].repeat( + len(batched_positions), axis=0 + ) + + with server.atomic(): + handle = server.scene.add_batched_meshes_trimesh( + "/robots_batched", + robot_mesh, + batched_positions=batched_positions, + batched_wxyzs=batched_wxyzs, + ) + state["robot_handles"].append(handle) + status_label.content = "**Status:** Ready" + + def update_terrain(): + nonlocal terrain_handle + status_label.content = "**Status:** Generating terrain..." + + if state["preset_name"] == "All Terrains": + # Create a copy with equal proportions to ensure all are shown once. + sub_terrains = {} + for name, cfg in available_presets.items(): + new_cfg = dataclasses.replace(cfg, proportion=1.0) + sub_terrains[name] = new_cfg + num_cols = len(sub_terrains) + num_rows = state["rows"] + else: + selected_instance = available_presets[state["preset_name"]] + terrain_type = type(selected_instance) + + # Instantiate sub-terrain config with current GUI state. + sub_cfg_params = {} + for field in dataclasses.fields(terrain_type): + if field.name in ["proportion", "size", "flat_patch_sampling"]: + sub_cfg_params[field.name] = getattr(selected_instance, field.name) + continue + + if "range" in field.name and isinstance( + getattr(selected_instance, field.name), (tuple, list) + ): + if field.name + "_min" in state["params"]: + sub_cfg_params[field.name] = ( + state["params"][field.name + "_min"], + state["params"][field.name + "_max"], + ) + else: + sub_cfg_params[field.name] = getattr(selected_instance, field.name) + elif field.name in state["params"]: + sub_cfg_params[field.name] = state["params"][field.name] + else: + sub_cfg_params[field.name] = getattr(selected_instance, field.name) + + try: + sub_cfg = terrain_type(**sub_cfg_params) + except Exception as e: + print(f"Error creating config: {e}") + return + + num_rows = state["rows"] + num_cols = state["cols"] + sub_terrains = {state["preset_name"]: sub_cfg} + + generator_cfg = TerrainGeneratorCfg( + seed=state["seed"], + size=state["size"], + num_rows=num_rows, + num_cols=num_cols, + curriculum=True, + difficulty_range=state["difficulty_range"], + sub_terrains=sub_terrains, + add_lights=True, + ) + + generator = TerrainGenerator(generator_cfg) + spec = mujoco.MjSpec() + generator.compile(spec) + + # Save terrain metadata for robot spawning. + state["terrain_origins"] = generator.terrain_origins + + status_label.content = "**Status:** Compiling MuJoCo model..." + model = spec.compile() + data = mujoco.MjData(model) + + mujoco.mj_forward(model, data) + + # Find terrain geoms. + terrain_body_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_BODY, "terrain") + terrain_geom_ids = [ + i for i in range(model.ngeom) if model.geom_bodyid[i] == terrain_body_id + ] + + if not terrain_geom_ids: + status_label.content = "**Status:** Error: No terrain geoms found" + print("No terrain geoms found.") + return + + status_label.content = ( + f"**Status:** Merging {len(terrain_geom_ids)} terrain geoms..." + ) + terrain_mesh = merge_geoms(model, terrain_geom_ids) + num_faces = len(terrain_mesh.faces) + polygon_count_label.content = f"**Number of Polygons:** {num_faces:,}" + + # Remove old terrain mesh if exists. + if terrain_handle is not None: + terrain_handle.remove() + + status_label.content = "**Status:** Uploading terrain mesh..." + terrain_handle = server.scene.add_mesh_trimesh( + "/terrain", + terrain_mesh, + ) + + # Trigger robot update. + update_robots() + + # GUI Setup. + gui_params_folder = server.gui.add_folder("Terrain Parameters") + param_controls: List[Any] = [] + + def rebuild_gui(): + nonlocal param_controls + for control in param_controls: + control.remove() + param_controls.clear() + + if state["preset_name"] == "All Terrains": + with gui_params_folder: + md = server.gui.add_markdown( + "_Parameters not available for 'All Terrains' mode._" + ) + param_controls.append(md) + return + + selected_instance = available_presets[state["preset_name"]] + terrain_type = type(selected_instance) + fields = dataclasses.fields(terrain_type) + + with gui_params_folder: + for field in fields: + if field.name in ["proportion", "size", "flat_patch_sampling"]: + continue + + # Get type as string for comparison (handles future annotations). + type_str = str(field.type) + + # Check for range tuples first. + if "range" in field.name and isinstance( + getattr(selected_instance, field.name), (tuple, list) + ): + hint = PARAM_HINTS.get(field.name, (0.0, 1.0, 0.01)) + + val_min, val_max = getattr(selected_instance, field.name) + + # Store in state if not present. + if field.name + "_min" not in state["params"]: + state["params"][field.name + "_min"] = val_min + state["params"][field.name + "_max"] = val_max + + cur_min = state["params"][field.name + "_min"] + cur_max = state["params"][field.name + "_max"] + + v_min, v_max, v_step = hint + # Ensure range is valid for sliders. + if cur_min is not None: + v_min = min(v_min, cur_min) + else: + cur_min = v_min + + if cur_max is not None: + v_max = max(v_max, cur_max) + else: + cur_max = v_max + + s_min = server.gui.add_slider( + f"{field.name} min", + min=v_min, + max=v_max, + step=v_step, + initial_value=cur_min, + ) + s_max = server.gui.add_slider( + f"{field.name} max", + min=v_min, + max=v_max, + step=v_step, + initial_value=cur_max, + ) + + @s_min.on_update + def _(event, name=field.name): + state["params"][name + "_min"] = event.target.value + update_terrain() + + @s_max.on_update + def _(event, name=field.name): + state["params"][name + "_max"] = event.target.value + update_terrain() + + param_controls.extend([s_min, s_max]) + + elif "float" in type_str or "int" in type_str or field.type in [float, int]: + hint = PARAM_HINTS.get(field.name, (0.0, 10.0, 0.1)) + val = getattr(selected_instance, field.name) + + if field.name not in state["params"]: + state["params"][field.name] = val + + cur_val = state["params"][field.name] + v_min, v_max, v_step = hint + if cur_val is not None: + v_min = min(v_min, cur_val) + v_max = max(v_max, cur_val) + else: + cur_val = (v_min + v_max) / 2.0 + + slider = server.gui.add_slider( + field.name, min=v_min, max=v_max, step=v_step, initial_value=cur_val + ) + + @slider.on_update + def _( + event, name=field.name, is_int=("int" in type_str) or field.type is int + ): + val = event.target.value + if is_int: + val = int(val) + state["params"][name] = val + update_terrain() + + param_controls.append(slider) + + elif "bool" in type_str or field.type is bool: + val = getattr(selected_instance, field.name) + if field.name not in state["params"]: + state["params"][field.name] = val + + checkbox = server.gui.add_checkbox( + field.name, initial_value=state["params"][field.name] + ) + + @checkbox.on_update + def _(event, name=field.name): + state["params"][name] = event.target.value + update_terrain() + + param_controls.append(checkbox) + else: + # Fallback for other simple types if they have a default value. + try: + val = getattr(selected_instance, field.name) + if isinstance(val, (int, float)): + if field.name not in state["params"]: + state["params"][field.name] = val + slider = server.gui.add_slider( + field.name, + min=min(0.0, val), + max=max(10.0, val), + step=0.1, + initial_value=val, + ) + + @slider.on_update + def _(event, name=field.name): + state["params"][name] = event.target.value + update_terrain() + + param_controls.append(slider) + except Exception: + pass + + # Global Controls. + with server.gui.add_folder("Global Settings"): + preset_select = server.gui.add_dropdown( + "Preset", options=preset_names, initial_value=state["preset_name"] + ) + + @preset_select.on_update + def _(event): + state["preset_name"] = event.target.value + state["params"] = {} # Clear local overrides for new preset. + rebuild_gui() + update_terrain() + + seed_input = server.gui.add_number("Seed", initial_value=int(state["seed"])) + + @seed_input.on_update + def _(event): + state["seed"] = int(event.target.value) + update_terrain() + + robot_select = server.gui.add_dropdown( + "Robot", options=list(ROBOT_CFG_GETTERS.keys()), initial_value=state["robot_name"] + ) + + @robot_select.on_update + def _(event): + state["robot_name"] = event.target.value + update_robots() + + btn_randomize = server.gui.add_button("Randomize Seed") + + @btn_randomize.on_click + def _(_): + new_seed = np.random.randint(0, 10000) + seed_input.value = new_seed + state["seed"] = int(new_seed) + update_terrain() + + btn_reset_camera = server.gui.add_button("Reset Camera") + + @btn_reset_camera.on_click + def _(_): + for client in server.get_clients().values(): + client.camera.position = (10, 10, 10) + client.camera.look_at = (0, 0, 0) + + # Initialize. + rebuild_gui() + update_terrain() + + print("Viser Terrain Visualizer running...") + while True: + time.sleep(1.0) + + +if __name__ == "__main__": + main() diff --git a/mjlab/src/mjlab/sensor/__init__.py b/mjlab/src/mjlab/sensor/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..b13177257173926aeb5d6ce95c3d6a5f21fec976 --- /dev/null +++ b/mjlab/src/mjlab/sensor/__init__.py @@ -0,0 +1,20 @@ +from mjlab.sensor.builtin_sensor import BuiltinSensor as BuiltinSensor +from mjlab.sensor.builtin_sensor import BuiltinSensorCfg as BuiltinSensorCfg +from mjlab.sensor.builtin_sensor import ObjRef as ObjRef +from mjlab.sensor.camera_sensor import CameraSensor as CameraSensor +from mjlab.sensor.camera_sensor import CameraSensorCfg as CameraSensorCfg +from mjlab.sensor.camera_sensor import CameraSensorData as CameraSensorData +from mjlab.sensor.contact_sensor import ContactData as ContactData +from mjlab.sensor.contact_sensor import ContactMatch as ContactMatch +from mjlab.sensor.contact_sensor import ContactSensor as ContactSensor +from mjlab.sensor.contact_sensor import ContactSensorCfg as ContactSensorCfg +from mjlab.sensor.raycast_sensor import GridPatternCfg as GridPatternCfg +from mjlab.sensor.raycast_sensor import ( + PinholeCameraPatternCfg as PinholeCameraPatternCfg, +) +from mjlab.sensor.raycast_sensor import RayCastData as RayCastData +from mjlab.sensor.raycast_sensor import RayCastSensor as RayCastSensor +from mjlab.sensor.raycast_sensor import RayCastSensorCfg as RayCastSensorCfg +from mjlab.sensor.sensor import Sensor as Sensor +from mjlab.sensor.sensor import SensorCfg as SensorCfg +from mjlab.sensor.sensor_context import SensorContext as SensorContext diff --git a/mjlab/src/mjlab/sensor/builtin_sensor.py b/mjlab/src/mjlab/sensor/builtin_sensor.py new file mode 100644 index 0000000000000000000000000000000000000000..fb38dad83613ce639c223239f8056f4532d42fd3 --- /dev/null +++ b/mjlab/src/mjlab/sensor/builtin_sensor.py @@ -0,0 +1,343 @@ +"""Sensors that wrap MuJoCo builtin sensors.""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import Literal + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.entity import Entity +from mjlab.sensor.sensor import Sensor, SensorCfg + +SensorType = Literal[ + # Site sensors. + "accelerometer", + "velocimeter", + "gyro", + "force", + "torque", + "magnetometer", + "rangefinder", + # Joint sensors. + "jointpos", + "jointvel", + "jointlimitpos", + "jointlimitvel", + "jointlimitfrc", + "jointactuatorfrc", + # Tendon sensors. + "tendonpos", + "tendonvel", + "tendonactuatorfrc", + # Actuator sensors. + "actuatorpos", + "actuatorvel", + "actuatorfrc", + # Frame sensors. + "framepos", + "framequat", + "framexaxis", + "frameyaxis", + "framezaxis", + "framelinvel", + "frameangvel", + "framelinacc", + "frameangacc", + # Subtree sensors. + "subtreecom", + "subtreelinvel", + "subtreeangmom", + # Misc. + "e_potential", + "e_kinetic", + "clock", +] + +_SENSOR_TYPE_MAP = { + # Site sensors. + "accelerometer": mujoco.mjtSensor.mjSENS_ACCELEROMETER, + "velocimeter": mujoco.mjtSensor.mjSENS_VELOCIMETER, + "gyro": mujoco.mjtSensor.mjSENS_GYRO, + "force": mujoco.mjtSensor.mjSENS_FORCE, + "torque": mujoco.mjtSensor.mjSENS_TORQUE, + "magnetometer": mujoco.mjtSensor.mjSENS_MAGNETOMETER, + "rangefinder": mujoco.mjtSensor.mjSENS_RANGEFINDER, + # Joint sensors. + "jointpos": mujoco.mjtSensor.mjSENS_JOINTPOS, + "jointvel": mujoco.mjtSensor.mjSENS_JOINTVEL, + "jointlimitpos": mujoco.mjtSensor.mjSENS_JOINTLIMITPOS, + "jointlimitvel": mujoco.mjtSensor.mjSENS_JOINTLIMITVEL, + "jointlimitfrc": mujoco.mjtSensor.mjSENS_JOINTLIMITFRC, + "jointactuatorfrc": mujoco.mjtSensor.mjSENS_JOINTACTFRC, + # Tendon sensors. + "tendonpos": mujoco.mjtSensor.mjSENS_TENDONPOS, + "tendonvel": mujoco.mjtSensor.mjSENS_TENDONVEL, + "tendonactuatorfrc": mujoco.mjtSensor.mjSENS_TENDONACTFRC, + # Actuator sensors. + "actuatorpos": mujoco.mjtSensor.mjSENS_ACTUATORPOS, + "actuatorvel": mujoco.mjtSensor.mjSENS_ACTUATORVEL, + "actuatorfrc": mujoco.mjtSensor.mjSENS_ACTUATORFRC, + # Frame sensors. + "framepos": mujoco.mjtSensor.mjSENS_FRAMEPOS, + "framequat": mujoco.mjtSensor.mjSENS_FRAMEQUAT, + "framexaxis": mujoco.mjtSensor.mjSENS_FRAMEXAXIS, + "frameyaxis": mujoco.mjtSensor.mjSENS_FRAMEYAXIS, + "framezaxis": mujoco.mjtSensor.mjSENS_FRAMEZAXIS, + "framelinvel": mujoco.mjtSensor.mjSENS_FRAMELINVEL, + "frameangvel": mujoco.mjtSensor.mjSENS_FRAMEANGVEL, + "framelinacc": mujoco.mjtSensor.mjSENS_FRAMELINACC, + "frameangacc": mujoco.mjtSensor.mjSENS_FRAMEANGACC, + # Subtree sensors. + "subtreecom": mujoco.mjtSensor.mjSENS_SUBTREECOM, + "subtreelinvel": mujoco.mjtSensor.mjSENS_SUBTREELINVEL, + "subtreeangmom": mujoco.mjtSensor.mjSENS_SUBTREEANGMOM, + # Misc. + "clock": mujoco.mjtSensor.mjSENS_CLOCK, + "e_potential": mujoco.mjtSensor.mjSENS_E_POTENTIAL, + "e_kinetic": mujoco.mjtSensor.mjSENS_E_KINETIC, +} + +_OBJECT_TYPE_MAP = { + "body": mujoco.mjtObj.mjOBJ_BODY, + "xbody": mujoco.mjtObj.mjOBJ_XBODY, + "joint": mujoco.mjtObj.mjOBJ_JOINT, + "geom": mujoco.mjtObj.mjOBJ_GEOM, + "site": mujoco.mjtObj.mjOBJ_SITE, + "actuator": mujoco.mjtObj.mjOBJ_ACTUATOR, + "tendon": mujoco.mjtObj.mjOBJ_TENDON, + "camera": mujoco.mjtObj.mjOBJ_CAMERA, +} + +_SENSORS_REQUIRING_SITE = { + "accelerometer", + "velocimeter", + "gyro", + "force", + "torque", + "magnetometer", + "rangefinder", +} + +_SENSORS_REQUIRING_SPATIAL_FRAME = { + "framepos", + "framequat", + "framexaxis", + "frameyaxis", + "framezaxis", + "framelinvel", + "frameangvel", + "framelinacc", + "frameangacc", +} + +_SENSORS_REQUIRING_BODY = { + "subtreecom", + "subtreelinvel", + "subtreeangmom", +} + +_SENSOR_OBJECT_REQUIREMENTS = { + "jointpos": "joint", + "jointvel": "joint", + "jointlimitpos": "joint", + "jointlimitvel": "joint", + "jointlimitfrc": "joint", + "jointactuatorfrc": "joint", + "tendonpos": "tendon", + "tendonvel": "tendon", + "tendonactuatorfrc": "tendon", + "actuatorpos": "actuator", + "actuatorvel": "actuator", + "actuatorfrc": "actuator", +} + +_SPATIAL_FRAME_TYPES = {"body", "xbody", "geom", "site", "camera"} +_SENSORS_ALLOWING_REF = { + "framepos", + "framequat", + "framexaxis", + "frameyaxis", + "framezaxis", + "framelinvel", + "frameangvel", + "framelinacc", + "frameangacc", +} + + +@dataclass +class ObjRef: + """Reference to a MuJoCo object (body, joint, site, etc.). + + Used to specify which object a sensor is attached to and its frame of reference. + The entity field allows scoping objects to specific entity namespaces. + """ + + type: Literal[ + "body", "xbody", "joint", "geom", "site", "actuator", "tendon", "camera" + ] + """Type of the object.""" + name: str + """Name of the object.""" + entity: str | None = None + """Optional entity prefix for the object name.""" + + def prefixed_name(self) -> str: + """Get the full name with entity prefix if applicable.""" + if self.entity: + return f"{self.entity}/{self.name}" + return self.name + + +@dataclass +class BuiltinSensorCfg(SensorCfg): + sensor_type: SensorType + """Which builtin sensor to use.""" + obj: ObjRef | None = None + """The type and name of the object the sensor is attached to.""" + ref: ObjRef | None = None + """The type and name of object to which the frame-of-reference is attached to.""" + cutoff: float = 0.0 + """When this value is positive, it limits the absolute value of the sensor output.""" + + def __post_init__(self) -> None: + # Auto-prefix sensor name if it references an entity. + if self.obj is not None and self.obj.entity is not None: + self.name = f"{self.obj.entity}/{self.name}" + + if self.sensor_type in _SENSORS_REQUIRING_SITE: + if self.obj is None: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj with type='site'" + ) + if self.obj.type != "site": + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj.type='site', got " + f"'{self.obj.type}'" + ) + + elif self.sensor_type in _SENSORS_REQUIRING_SPATIAL_FRAME: + if self.obj is None: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj with spatial frame" + ) + if self.obj.type not in _SPATIAL_FRAME_TYPES: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj.type in " + f"{_SPATIAL_FRAME_TYPES}, got '{self.obj.type}'" + ) + + elif self.sensor_type in _SENSORS_REQUIRING_BODY: + if self.obj is None: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj with type='body'" + ) + if self.obj.type != "body": + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj.type='body', " + f"got '{self.obj.type}'" + ) + + elif self.sensor_type in _SENSOR_OBJECT_REQUIREMENTS: + required_type = _SENSOR_OBJECT_REQUIREMENTS[self.sensor_type] + if self.obj is None: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj with type='{required_type}'" + ) + if self.obj.type != required_type: + raise ValueError( + f"Sensor type '{self.sensor_type}' requires obj.type='{required_type}', " + f"got '{self.obj.type}'" + ) + + if self.ref is not None and self.sensor_type not in _SENSORS_ALLOWING_REF: + raise ValueError( + f"Sensor type '{self.sensor_type}' does not support ref specification" + ) + + def build(self) -> BuiltinSensor: + return BuiltinSensor(self) + + +class BuiltinSensor(Sensor[torch.Tensor]): + """Wrapper over MuJoCo builtin sensors. + + Can add a new sensor to the spec, or wrap an existing sensor from entity XML. + Returns raw MuJoCo sensordata as torch.Tensor with shape depending on sensor type + (e.g., accelerometer: (N, 3), framequat: (N, 4)). + + Note: Caching provides minimal benefit here since data access is just a tensor + slice view into MuJoCo's sensordata buffer. + """ + + def __init__( + self, cfg: BuiltinSensorCfg | None = None, name: str | None = None + ) -> None: + super().__init__() + if cfg is not None: + self._name = cfg.name + self.cfg: BuiltinSensorCfg | None = cfg + else: + assert name is not None, "Must provide either cfg or name" + self._name = name + self.cfg = None + self._data: mjwarp.Data | None = None + self._data_view: torch.Tensor | None = None + + @classmethod + def from_existing(cls, name: str) -> BuiltinSensor: + """Wrap an existing sensor already defined in entity XML.""" + return cls(cfg=None, name=name) + + def edit_spec(self, scene_spec: mujoco.MjSpec, entities: dict[str, Entity]) -> None: + del entities + if self.cfg is None: + return + + # Check for duplicate sensors. + for sensor in scene_spec.sensors: + if sensor.name == self.cfg.name: + is_entity_scoped = self.cfg.obj is not None and self.cfg.obj.entity is not None + if is_entity_scoped: + raise ValueError( + f"Sensor '{self.cfg.name}' is defined in both entity XML and scene config. " + f"Remove the sensor definition from the entity XML file, or remove the " + f"BuiltinSensorCfg from scene.sensors." + ) + else: + raise ValueError( + f"Sensor '{self.cfg.name}' already exists in the scene. " + f"Rename this sensor to avoid conflicts." + ) + + # Add sensor to spec. + scene_spec.add_sensor( + name=self.cfg.name, + type=_SENSOR_TYPE_MAP[self.cfg.sensor_type], + objtype=( + _OBJECT_TYPE_MAP[self.cfg.obj.type] if self.cfg.obj is not None else None + ), + objname=(self.cfg.obj.prefixed_name() if self.cfg.obj is not None else None), + reftype=( + _OBJECT_TYPE_MAP[self.cfg.ref.type] if self.cfg.ref is not None else None + ), + refname=(self.cfg.ref.prefixed_name() if self.cfg.ref is not None else None), + cutoff=self.cfg.cutoff if self.cfg.cutoff > 0 else None, + ) + + def initialize( + self, mj_model: mujoco.MjModel, model: mjwarp.Model, data: mjwarp.Data, device: str + ) -> None: + del model, device + self._data = data + sensor = mj_model.sensor(self._name) + start = sensor.adr[0] + dim = sensor.dim[0] + self._data_view = self._data.sensordata[:, start : start + dim] + + def _compute_data(self) -> torch.Tensor: + assert self._data_view is not None + return self._data_view diff --git a/mjlab/src/mjlab/sensor/camera_sensor.py b/mjlab/src/mjlab/sensor/camera_sensor.py new file mode 100644 index 0000000000000000000000000000000000000000..4f2b8d759dea0bea1d7f8ce8755becb5928d40e4 --- /dev/null +++ b/mjlab/src/mjlab/sensor/camera_sensor.py @@ -0,0 +1,217 @@ +"""Camera sensor for RGB and depth rendering.""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Literal + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.entity import Entity +from mjlab.sensor.sensor import Sensor, SensorCfg + +if TYPE_CHECKING: + from mjlab.sensor.sensor_context import SensorContext + +CameraDataType = Literal["rgb", "depth"] + +# Default MuJoCo fov, in degrees. +_DEFAULT_CAM_FOVY = 45.0 + + +@dataclass +class CameraSensorCfg(SensorCfg): + """Configuration for a camera sensor. + + A camera sensor can either wrap an existing MuJoCo camera + (``camera_name``) or create a new one at the specified + pos/quat. New cameras are added to the worldbody by default, + or to a specific body via ``parent_body``. + + Note: + All camera sensors in a scene must share identical values for + use_textures, use_shadows, and enabled_geom_groups. This is a + constraint of the underlying mujoco_warp rendering system. + """ + + camera_name: str | None = None + """Name of an existing MuJoCo camera to wrap. + + If None, a new camera is created using pos/quat/fovy. + If set, the sensor wraps the named camera instead of creating one. + """ + + parent_body: str | None = None + """Parent body to attach a new camera to. + + Only used when ``camera_name`` is None (creating a new camera). + If None, the camera is added to the worldbody. Use the full + prefixed name (e.g., "robot/link_6") to attach to an entity's + body. The pos/quat are then relative to the parent body frame. + """ + + pos: tuple[float, float, float] = (0.0, 0.0, 1.0) + """Camera position (used when creating a new camera). + + World-frame if parent_body is None, otherwise relative to the + parent body frame. + """ + + quat: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0) + """Camera orientation quaternion (w, x, y, z).""" + + fovy: float | None = None + """Vertical field of view in degrees. None uses MuJoCo default.""" + + width: int = 160 + """Image width in pixels.""" + + height: int = 120 + """Image height in pixels.""" + + data_types: tuple[CameraDataType, ...] = ("rgb",) + """Data types to capture: any combination of "rgb" and "depth".""" + + use_textures: bool = True + """Whether to use textures in rendering.""" + + use_shadows: bool = False + """Whether to use shadows in rendering.""" + + enabled_geom_groups: tuple[int, ...] = (0, 1, 2) + """Geom groups (0-5) visible to the camera.""" + + orthographic: bool = False + """Use orthographic projection instead of perspective.""" + + clone_data: bool = False + """If True, clone tensors on each access. + + Set to True if you modify the returned data in-place. + """ + + def __post_init__(self) -> None: + valid = {"rgb", "depth"} + invalid = {dt for dt in self.data_types if dt not in valid} + if invalid: + raise ValueError(f"Invalid camera data types: {invalid}. Valid types: {valid}") + if not self.data_types: + raise ValueError("At least one data type must be specified.") + + def build(self) -> CameraSensor: + return CameraSensor(self) + + +@dataclass +class CameraSensorData: + """Camera sensor output data. + + Shapes: + - rgb: [num_envs, height, width, 3] (uint8) + - depth: [num_envs, height, width, 1] (float32) + """ + + rgb: torch.Tensor | None = None + """RGB image [num_envs, height, width, 3] (uint8). None if not + enabled.""" + + depth: torch.Tensor | None = None + """Depth image [num_envs, height, width, 1] (float32). None if not + enabled.""" + + +class CameraSensor(Sensor[CameraSensorData]): + """Camera sensor for RGB and depth rendering.""" + + requires_sensor_context = True + + def __init__(self, cfg: CameraSensorCfg) -> None: + super().__init__() + self.cfg = cfg + self._camera_name = cfg.camera_name if cfg.camera_name is not None else cfg.name + self._is_wrapping_existing = cfg.camera_name is not None + self._ctx: SensorContext | None = None + self._camera_idx: int = -1 + + @property + def camera_name(self) -> str: + return self._camera_name + + @property + def camera_idx(self) -> int: + return self._camera_idx + + def edit_spec( + self, + scene_spec: mujoco.MjSpec, + entities: dict[str, Entity], + ) -> None: + del entities + + if self._is_wrapping_existing: + cam = scene_spec.camera(self._camera_name) + assert isinstance(cam, mujoco.MjsCamera) + if self.cfg.fovy is not None: + cam.fovy = self.cfg.fovy + if self.cfg.orthographic: + cam.proj = mujoco.mjtProjection.mjPROJ_ORTHOGRAPHIC + return + + if self.cfg.parent_body is not None: + parent = scene_spec.body(self.cfg.parent_body) + else: + parent = scene_spec.worldbody + + proj = ( + mujoco.mjtProjection.mjPROJ_ORTHOGRAPHIC + if self.cfg.orthographic + else mujoco.mjtProjection.mjPROJ_PERSPECTIVE + ) + parent.add_camera( + name=self.cfg.name, + pos=self.cfg.pos, + quat=self.cfg.quat, + fovy=self.cfg.fovy if self.cfg.fovy is not None else _DEFAULT_CAM_FOVY, + resolution=[self.cfg.width, self.cfg.height], + proj=proj, + ) + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + del model, data, device + + try: + cam = mj_model.camera(self._camera_name) + self._camera_idx = cam.id + except KeyError as e: + available = [mj_model.camera(i).name for i in range(mj_model.ncam)] + raise ValueError( + f"Camera '{self._camera_name}' not found in model. Available: {available}" + ) from e + + def set_context(self, ctx: SensorContext) -> None: + self._ctx = ctx + + def _compute_data(self) -> CameraSensorData: + if self._ctx is None: + raise RuntimeError( + "CameraSensor requires a SensorContext. " + "Ensure the sensor is part of a scene with " + "sim.sense() calls." + ) + rgb_data = None + depth_data = None + if "rgb" in self.cfg.data_types: + rgb = self._ctx.get_rgb(self._camera_idx) + rgb_data = rgb.clone() if self.cfg.clone_data else rgb + if "depth" in self.cfg.data_types: + depth = self._ctx.get_depth(self._camera_idx) + depth_data = depth.clone() if self.cfg.clone_data else depth + return CameraSensorData(rgb=rgb_data, depth=depth_data) diff --git a/mjlab/src/mjlab/sensor/contact_sensor.py b/mjlab/src/mjlab/sensor/contact_sensor.py new file mode 100644 index 0000000000000000000000000000000000000000..2b44bea0d55b241af0105b402f62b82c8887fae5 --- /dev/null +++ b/mjlab/src/mjlab/sensor/contact_sensor.py @@ -0,0 +1,602 @@ +"""Contact sensors track collisions between geoms, bodies, or subtrees.""" + +from __future__ import annotations + +import re +from dataclasses import dataclass +from typing import Any, Literal + +import mujoco +import mujoco_warp as mjwarp +import torch + +from mjlab.entity import Entity +from mjlab.sensor.sensor import Sensor, SensorCfg + +_CONTACT_DATA_MAP = { + "found": 0, + "force": 1, + "torque": 2, + "dist": 3, + "pos": 4, + "normal": 5, + "tangent": 6, +} + +_CONTACT_DATA_DIMS = { + "found": 1, + "force": 3, + "torque": 3, + "dist": 1, + "pos": 3, + "normal": 3, + "tangent": 3, +} + +_CONTACT_REDUCE_MAP = { + "none": 0, + "mindist": 1, + "maxforce": 2, + "netforce": 3, +} + +_MODE_TO_OBJTYPE = { + "geom": mujoco.mjtObj.mjOBJ_GEOM, + "body": mujoco.mjtObj.mjOBJ_BODY, + "subtree": mujoco.mjtObj.mjOBJ_XBODY, +} + + +@dataclass +class ContactMatch: + """Specifies what to match on one side of a contact. + + mode: "geom", "body", or "subtree" + pattern: Regex or tuple of regexes (expands within entity if specified) + entity: Entity name to search within (None = treat pattern as literal MuJoCo name) + exclude: Filter out matches using these regex patterns or exact names. + """ + + mode: Literal["geom", "body", "subtree"] + pattern: str | tuple[str, ...] + entity: str | None = None + exclude: tuple[str, ...] = () + + +@dataclass +class ContactSensorCfg(SensorCfg): + """Tracks contacts between primary and secondary patterns. + + Output shape: [B, N * num_slots] or [B, N * num_slots, 3] where N = # of primaries + + Fields (choose subset): + - found: 0=no contact, >0=match count before reduction + - force, torque: 3D vectors in contact frame (or global if reduce="netforce") + - dist: penetration depth + - pos, normal, tangent: 3D vectors in global frame (normal: primary→secondary) + + Reduction modes (selects top num_slots from all matches): + - "none": fast, non-deterministic + - "mindist", "maxforce": closest/strongest contacts + - "netforce": sum all forces (global frame) + + Policies: + - secondary_policy: "first", "any", or "error" when secondary matches multiple + - track_air_time: enables landing/takeoff detection + - global_frame: rotates force/torque to global (requires normal+tangent fields) + """ + + primary: ContactMatch + secondary: ContactMatch | None = None + fields: tuple[str, ...] = ("found", "force") + reduce: Literal["none", "mindist", "maxforce", "netforce"] = "maxforce" + num_slots: int = 1 + secondary_policy: Literal["first", "any", "error"] = "first" + track_air_time: bool = False + global_frame: bool = False + history_length: int = 0 + """Number of substeps to store in history buffer for force/torque/dist fields. + + When 0 (default): No history buffer is allocated. History fields (force_history, + torque_history, dist_history) are None. Use the regular fields (force, torque, dist) + for the current instantaneous values. + + When >0: Allocates a history buffer that stores the last N substeps of contact data. + Shape is [B, N, history_length, ...] where index 0 is the most recent substep. + Set to your decimation value to capture all substeps within one policy step. + + Note: history_length=1 is redundant with the regular fields but provides a consistent + [B, N, H, ...] shape if your code expects a history dimension. + """ + debug: bool = False + + def build(self) -> ContactSensor: + return ContactSensor(self) + + +@dataclass +class _ContactSlot: + """Maps one MuJoCo sensor (one primary, one field) to its sensordata view.""" + + primary_name: str + field_name: str + sensor_name: str + data_view: torch.Tensor | None = None + + +@dataclass +class _AirTimeState: + """Tracks how long contacts have been in air/contact. Shape: [B, N].""" + + current_air_time: torch.Tensor + last_air_time: torch.Tensor + current_contact_time: torch.Tensor + last_contact_time: torch.Tensor + last_time: torch.Tensor + + +@dataclass +class ContactData: + """Contact sensor output (only requested fields are populated).""" + + found: torch.Tensor | None = None + """[B, N] 0=no contact, >0=match count""" + force: torch.Tensor | None = None + """[B, N, 3] contact frame (global if reduce="netforce" or global_frame=True)""" + torque: torch.Tensor | None = None + """[B, N, 3] contact frame (global if reduce="netforce" or global_frame=True)""" + dist: torch.Tensor | None = None + """[B, N] penetration depth""" + pos: torch.Tensor | None = None + """[B, N, 3] global frame""" + normal: torch.Tensor | None = None + """[B, N, 3] global frame, primary→secondary""" + tangent: torch.Tensor | None = None + """[B, N, 3] global frame""" + + current_air_time: torch.Tensor | None = None + """[B, N] time in air (if track_air_time=True)""" + last_air_time: torch.Tensor | None = None + """[B, N] duration of last air phase (if track_air_time=True)""" + current_contact_time: torch.Tensor | None = None + """[B, N] time in contact (if track_air_time=True)""" + last_contact_time: torch.Tensor | None = None + """[B, N] duration of last contact phase (if track_air_time=True)""" + + force_history: torch.Tensor | None = None + """[B, N, H, 3] contact forces over last H substeps (index 0 = most recent)""" + torque_history: torch.Tensor | None = None + """[B, N, H, 3] contact torques over last H substeps (index 0 = most recent)""" + dist_history: torch.Tensor | None = None + """[B, N, H] penetration depth over last H substeps (index 0 = most recent)""" + + +class ContactSensor(Sensor[ContactData]): + """Tracks contacts with automatic pattern expansion to multiple MuJoCo sensors.""" + + def __init__(self, cfg: ContactSensorCfg) -> None: + super().__init__() + self.cfg = cfg + + if cfg.global_frame and cfg.reduce != "netforce": + if "normal" not in cfg.fields or "tangent" not in cfg.fields: + raise ValueError( + f"Sensor '{cfg.name}': global_frame=True requires 'normal' and 'tangent' " + "in fields (needed to build rotation matrix)" + ) + + self._slots: list[_ContactSlot] = [] + self._data: mjwarp.Data | None = None + self._device: str | None = None + self._air_time_state: _AirTimeState | None = None + self._history_state: dict[str, torch.Tensor] | None = None + + def edit_spec(self, scene_spec: mujoco.MjSpec, entities: dict[str, Entity]) -> None: + """Expand patterns and add MuJoCo sensors (one per primary x field pair).""" + self._slots.clear() + + primary_names = self._resolve_primary_names(entities, self.cfg.primary) + if self.cfg.secondary is None or self.cfg.secondary_policy == "any": + secondary_name = None + else: + secondary_name = self._resolve_single_secondary( + entities, self.cfg.secondary, self.cfg.secondary_policy + ) + + for prim in primary_names: + for field in self.cfg.fields: + sensor_name = f"{self.cfg.name}_{prim}_{field}" + + self._add_contact_sensor_to_spec( + scene_spec, sensor_name, prim, secondary_name, field + ) + + self._slots.append( + _ContactSlot( + primary_name=prim, + field_name=field, + sensor_name=sensor_name, + ) + ) + + def initialize( + self, mj_model: mujoco.MjModel, model: mjwarp.Model, data: mjwarp.Data, device: str + ) -> None: + """Map sensors to sensordata buffer and allocate air time state.""" + del model + + if not self._slots: + raise RuntimeError( + f"There was an error initializing contact sensor '{self.cfg.name}'" + ) + + for slot in self._slots: + sensor = mj_model.sensor(slot.sensor_name) + start = sensor.adr[0] + dim = sensor.dim[0] + slot.data_view = data.sensordata[:, start : start + dim] + + self._data = data + self._device = device + + if self.cfg.track_air_time: + n_envs = data.time.shape[0] + n_primary = len(set(slot.primary_name for slot in self._slots)) + self._air_time_state = _AirTimeState( + current_air_time=torch.zeros((n_envs, n_primary), device=device), + last_air_time=torch.zeros((n_envs, n_primary), device=device), + current_contact_time=torch.zeros((n_envs, n_primary), device=device), + last_contact_time=torch.zeros((n_envs, n_primary), device=device), + last_time=torch.zeros((n_envs,), device=device), + ) + + if self.cfg.history_length > 0: + n_envs = data.time.shape[0] + n_primary = len(set(slot.primary_name for slot in self._slots)) + n_contacts = n_primary * self.cfg.num_slots + h = self.cfg.history_length + self._history_state = {} + if "force" in self.cfg.fields: + self._history_state["force"] = torch.zeros( + (n_envs, n_contacts, h, 3), device=device + ) + if "torque" in self.cfg.fields: + self._history_state["torque"] = torch.zeros( + (n_envs, n_contacts, h, 3), device=device + ) + if "dist" in self.cfg.fields: + self._history_state["dist"] = torch.zeros( + (n_envs, n_contacts, h), device=device + ) + + def _compute_data(self) -> ContactData: + out = self._extract_sensor_data() + if self._air_time_state is not None: + out.current_air_time = self._air_time_state.current_air_time + out.last_air_time = self._air_time_state.last_air_time + out.current_contact_time = self._air_time_state.current_contact_time + out.last_contact_time = self._air_time_state.last_contact_time + if self._history_state is not None: + out.force_history = self._history_state.get("force") + out.torque_history = self._history_state.get("torque") + out.dist_history = self._history_state.get("dist") + return out + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + super().reset(env_ids) + if env_ids is None: + env_ids = slice(None) + + # Reset air time state for specified envs. + if self._air_time_state is not None: + self._air_time_state.current_air_time[env_ids] = 0.0 + self._air_time_state.last_air_time[env_ids] = 0.0 + self._air_time_state.current_contact_time[env_ids] = 0.0 + self._air_time_state.last_contact_time[env_ids] = 0.0 + if self._data is not None: + self._air_time_state.last_time[env_ids] = self._data.time[env_ids] + + # Reset history state for specified envs. + if self._history_state is not None: + for buf in self._history_state.values(): + buf[env_ids] = 0.0 + + def update(self, dt: float) -> None: + super().update(dt) + if self._air_time_state is not None: + self._update_air_time_tracking() + if self._history_state is not None: + self._update_history() + + def compute_first_contact(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: + """Returns [B, N] bool: True for contacts established within last dt seconds.""" + if self._air_time_state is None: + raise RuntimeError( + f"Sensor '{self.cfg.name}' must have track_air_time=True " + "to use compute_first_contact" + ) + is_in_contact = self._air_time_state.current_contact_time > 0.0 + within_dt = self._air_time_state.current_contact_time < (dt + abs_tol) + return is_in_contact & within_dt + + def compute_first_air(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: + """Returns [B, N] bool: True for contacts broken within last dt seconds.""" + if self._air_time_state is None: + raise RuntimeError( + f"Sensor '{self.cfg.name}' must have track_air_time=True " + "to use compute_first_air" + ) + is_in_air = self._air_time_state.current_air_time > 0.0 + within_dt = self._air_time_state.current_air_time < (dt + abs_tol) + return is_in_air & within_dt + + def _extract_sensor_data(self) -> ContactData: + if not self._slots: + raise RuntimeError(f"Sensor '{self.cfg.name}' not initialized") + + field_chunks: dict[str, list[torch.Tensor]] = {f: [] for f in self.cfg.fields} + + for slot in self._slots: + assert slot.data_view is not None + field_dim = _CONTACT_DATA_DIMS[slot.field_name] + raw = slot.data_view.view(slot.data_view.size(0), self.cfg.num_slots, field_dim) + field_chunks[slot.field_name].append(raw) + + out = ContactData() + for field, chunks in field_chunks.items(): + cat = torch.cat(chunks, dim=1) + if cat.size(-1) == 1: + cat = cat.squeeze(-1) + setattr(out, field, cat) + + if self.cfg.global_frame and self.cfg.reduce != "netforce": + out = self._transform_to_global_frame(out) + + return out + + def _transform_to_global_frame(self, data: ContactData) -> ContactData: + """Rotate force/torque from contact frame to global frame.""" + assert data.normal is not None and data.tangent is not None + + normal = data.normal + tangent = data.tangent + tangent2 = torch.cross(normal, tangent, dim=-1) + R = torch.stack([tangent, tangent2, normal], dim=-1) + + has_contact = torch.norm(normal, dim=-1, keepdim=True) > 1e-8 + + if data.force is not None: + force_global = torch.einsum("...ij,...j->...i", R, data.force) + data.force = torch.where(has_contact, force_global, data.force) + + if data.torque is not None: + torque_global = torch.einsum("...ij,...j->...i", R, data.torque) + data.torque = torch.where(has_contact, torque_global, data.torque) + + return data + + def _update_air_time_tracking(self) -> None: + assert self._air_time_state is not None + + contact_data = self._extract_sensor_data() + if contact_data.found is None or "found" not in self.cfg.fields: + return + + assert self._data is not None + current_time = self._data.time + elapsed_time = current_time - self._air_time_state.last_time + elapsed_time = elapsed_time.unsqueeze(-1) + + is_contact = contact_data.found > 0 + + state = self._air_time_state + is_first_contact = (state.current_air_time > 0) & is_contact + is_first_detached = (state.current_contact_time > 0) & ~is_contact + + state.last_air_time[:] = torch.where( + is_first_contact, + state.current_air_time + elapsed_time, + state.last_air_time, + ) + state.current_air_time[:] = torch.where( + ~is_contact, + state.current_air_time + elapsed_time, + torch.zeros_like(state.current_air_time), + ) + + state.last_contact_time[:] = torch.where( + is_first_detached, + state.current_contact_time + elapsed_time, + state.last_contact_time, + ) + state.current_contact_time[:] = torch.where( + is_contact, + state.current_contact_time + elapsed_time, + torch.zeros_like(state.current_contact_time), + ) + + state.last_time[:] = current_time + + def _update_history(self) -> None: + """Roll history buffer and insert current contact data at index 0.""" + assert self._history_state is not None + + contact_data = self._extract_sensor_data() + + if "force" in self._history_state and contact_data.force is not None: + self._history_state["force"] = self._history_state["force"].roll(1, dims=2) + self._history_state["force"][:, :, 0, :] = contact_data.force + + if "torque" in self._history_state and contact_data.torque is not None: + self._history_state["torque"] = self._history_state["torque"].roll(1, dims=2) + self._history_state["torque"][:, :, 0, :] = contact_data.torque + + if "dist" in self._history_state and contact_data.dist is not None: + self._history_state["dist"] = self._history_state["dist"].roll(1, dims=2) + self._history_state["dist"][:, :, 0] = contact_data.dist + + def _resolve_primary_names( + self, entities: dict[str, Entity], match: ContactMatch + ) -> list[str]: + if match.entity in (None, ""): + result = ( + [match.pattern] if isinstance(match.pattern, str) else list(match.pattern) + ) + return result + + if match.entity not in entities: + raise ValueError( + f"Primary entity '{match.entity}' not found. Available: {list(entities.keys())}" + ) + ent = entities[match.entity] + + patterns = [match.pattern] if isinstance(match.pattern, str) else match.pattern + + if match.mode == "geom": + _, names = ent.find_geoms(patterns) + elif match.mode == "body": + _, names = ent.find_bodies(patterns) + elif match.mode == "subtree": + _, names = ent.find_bodies(patterns) + if not names: + raise ValueError( + f"Primary subtree pattern '{match.pattern}' matched no bodies in " + f"'{match.entity}'" + ) + else: + raise ValueError("Primary mode must be one of {'geom','body','subtree'}") + + excludes = match.exclude + if excludes: + exclude_patterns = [] + exclude_exact = set() + for exc in excludes: + if any(c in exc for c in r".*+?[]{}()\|^$"): + exclude_patterns.append(re.compile(exc)) + else: + exclude_exact.add(exc) + if exclude_exact: + names = [n for n in names if n not in exclude_exact] + if exclude_patterns: + names = [n for n in names if not any(rx.search(n) for rx in exclude_patterns)] + + if not names: + raise ValueError( + f"Primary pattern '{match.pattern}' (after excludes) matched " + f"no names in '{match.entity}'" + ) + return names + + def _resolve_single_secondary( + self, + entities: dict[str, Entity], + match: ContactMatch, + policy: Literal["first", "any", "error"], + ) -> str | None: + if policy == "any": + return None + + if isinstance(match.pattern, tuple): + raise ValueError( + "Secondary must specify a single name (string). " + "Use a single exact name or a regex that resolves to one name, " + "or set secondary_policy='any' if you want no filter." + ) + + if match.entity in (None, ""): + if match.mode not in {"geom", "body", "subtree"}: + raise ValueError("Secondary mode must be one of {'geom','body','subtree'}") + return match.pattern + + if match.entity not in entities: + raise ValueError( + f"Secondary entity '{match.entity}' not found. " + f"Available: {list(entities.keys())}" + ) + ent = entities[match.entity] + + if match.mode == "subtree": + return match.pattern + + if match.mode == "geom": + _, names = ent.find_geoms(match.pattern) + elif match.mode == "body": + _, names = ent.find_bodies(match.pattern) + else: + raise ValueError("Secondary mode must be one of {'geom','body','subtree'}") + + if not names: + raise ValueError( + f"Secondary pattern '{match.pattern}' matched nothing in '{match.entity}'" + ) + + if len(names) == 1 or policy == "first": + return names[0] + + raise ValueError( + f"Secondary pattern '{match.pattern}' matched multiple: {names}. " + f"Be explicit or set secondary_policy='first' or 'any'." + ) + + def _add_contact_sensor_to_spec( + self, + scene_spec: mujoco.MjSpec, + sensor_name: str, + primary_name: str, + secondary_name: str | None, + field: str, + ) -> None: + data_bits = 1 << _CONTACT_DATA_MAP[field] + reduce_mode = _CONTACT_REDUCE_MAP[self.cfg.reduce] + intprm = [data_bits, reduce_mode, self.cfg.num_slots] + + primary_entity = self.cfg.primary.entity + if primary_entity and primary_entity != "": + prefixed_primary = f"{primary_entity}/{primary_name}" + else: + prefixed_primary = primary_name + + kwargs: dict[str, Any] = { + "name": sensor_name, + "type": mujoco.mjtSensor.mjSENS_CONTACT, + "objtype": _MODE_TO_OBJTYPE[self.cfg.primary.mode], + "objname": prefixed_primary, + "intprm": intprm, + } + + if secondary_name is not None: + assert self.cfg.secondary is not None + secondary_entity = self.cfg.secondary.entity + if secondary_entity and secondary_entity != "": + prefixed_secondary = f"{secondary_entity}/{secondary_name}" + else: + prefixed_secondary = secondary_name + kwargs["reftype"] = _MODE_TO_OBJTYPE[self.cfg.secondary.mode] + kwargs["refname"] = prefixed_secondary + + if self.cfg.debug: + + def _ename(v): + return getattr(v, "name", str(v)) + + objtype_name = _ename(kwargs["objtype"]).removeprefix("mjOBJ_") + reftype_val = kwargs.get("reftype") + refname_val = kwargs.get("refname") + reftype_name = ( + _ename(reftype_val).removeprefix("mjOBJ_") + if reftype_val is not None + else "" + ) + + ref_str = "" if refname_val is None else f"{reftype_name}:{refname_val}" + + print( + "Adding contact sensor\n" + f" name : {sensor_name}\n" + f" object : {objtype_name}:{kwargs['objname']}\n" + f" ref : {ref_str}\n" + f" field : {field} bits=0b{intprm[0]:b}\n" + f" reduce : {self.cfg.reduce} num_slots={self.cfg.num_slots}" + ) + + scene_spec.add_sensor(**kwargs) diff --git a/mjlab/src/mjlab/sensor/raycast_sensor.py b/mjlab/src/mjlab/sensor/raycast_sensor.py new file mode 100644 index 0000000000000000000000000000000000000000..013bb1f763130caae64f8f0cfcbe19c9c91ffb98 --- /dev/null +++ b/mjlab/src/mjlab/sensor/raycast_sensor.py @@ -0,0 +1,838 @@ +"""Raycast sensor for terrain and obstacle detection. + +Ray Patterns +------------ + +This module provides two ray pattern types for different use cases: + +**Grid Pattern** - Parallel rays in a 2D grid:: + + Camera at any height: + ↓ ↓ ↓ ↓ ↓ ← All rays point same direction + ↓ ↓ ↓ ↓ ↓ + ↓ ↓ ↓ ↓ ↓ + ──●───●───●───●───●── ← Fixed spacing (e.g., 10cm apart) + Ground + +- Rays are parallel (all point in the same direction, e.g., -Z down) +- Spacing is defined in world units (meters) +- Height doesn't affect the hit pattern - same footprint regardless of altitude +- Good for: height maps, terrain scanning with consistent spatial sampling + +**Pinhole Camera Pattern** - Diverging rays from a single point:: + + Camera LOW: Camera HIGH: + 📷 📷 + /|\\ / | \\ + / | \\ / | \\ + / | \\ / | \\ + ─●───●───●─ ───●─────●─────●─── + (small footprint) (large footprint) + +- Rays diverge from a single point (like light entering a camera) +- FOV is fixed in angular units (degrees) +- Higher altitude → wider ground coverage, more spread between hits +- Lower altitude → tighter ground coverage, denser hits +- Good for: simulating depth cameras, LiDAR with angular resolution + +**Pattern Comparison**: + +============== ==================== ========================== +Aspect Grid Pinhole +============== ==================== ========================== +Ray direction All parallel Diverge from origin +Spacing Meters Degrees (FOV) +Height affect No Yes +Real-world Orthographic proj. Perspective camera / LiDAR +============== ==================== ========================== + +The pinhole behavior matches real depth sensors (RealSense, LiDAR) - when +you're farther from an object, each pixel covers more area. + + +Frame Attachment +---------------- + +Rays are attached to a frame in the scene via ``ObjRef``. Supported frame types: + +- **body**: Attach to a body's origin. Rays follow body position and orientation. +- **site**: Attach to a site. Useful for precise placement or offset from body. +- **geom**: Attach to a geometry. Useful for sensors mounted on specific parts. + +Example:: + + from mjlab.sensor import ObjRef, RayCastSensorCfg, GridPatternCfg + + cfg = RayCastSensorCfg( + name="terrain_scan", + frame=ObjRef(type="body", name="base", entity="robot"), + pattern=GridPatternCfg(size=(1.0, 1.0), resolution=0.1), + ) + +The ``exclude_parent_body`` option (default: True) prevents rays from hitting +the body they're attached to. + + +Ray Alignment +------------- + +The ``ray_alignment`` setting controls how rays orient relative to the frame:: + + Robot tilted 30°: + + "base" (default) "yaw" "world" + Rays tilt with body Rays stay level Rays fixed to world + ↘ ↓ ↙ ↓ ↓ ↓ ↓ ↓ ↓ + \\|/ ||| ||| + 🤖 ← tilted 🤖 ← tilted 🤖 ← tilted + / / / + +- **base**: Full position + rotation. Rays rotate with the body. Good for + body-mounted sensors that should scan relative to the robot's orientation. + +- **yaw**: Position + yaw only, ignores pitch/roll. Rays always point straight + down regardless of body tilt. Good for height maps where you want consistent + vertical sampling even when the robot is on a slope. + +- **world**: Fixed in world frame, only position follows body. Rays always + point in a fixed world direction. Good for gravity-aligned measurements. + + +Debug Visualization +------------------- + +Enable visualization with ``debug_vis=True`` and customize via ``VizCfg``:: + + cfg = RayCastSensorCfg( + name="scan", + frame=ObjRef(type="body", name="base", entity="robot"), + pattern=GridPatternCfg(), + debug_vis=True, + viz=RayCastSensorCfg.VizCfg( + hit_color=(0, 1, 0, 0.8), # Green for hits + miss_color=(1, 0, 0, 0.4), # Red for misses + show_rays=True, # Draw ray arrows + show_normals=True, # Draw surface normals + normal_color=(1, 1, 0, 1), # Yellow normals + ), + ) + +Visualization options: + +- ``hit_color`` / ``miss_color``: RGBA colors for ray arrows +- ``hit_sphere_color`` / ``hit_sphere_radius``: Spheres at hit points +- ``show_rays``: Draw arrows from origin to hit/miss points +- ``show_normals`` / ``normal_color`` / ``normal_length``: Surface normal arrows + + +Geom Group Filtering +-------------------- + +MuJoCo geoms can be assigned to groups 0-5. Use ``include_geom_groups`` to +filter which groups the rays can hit:: + + cfg = RayCastSensorCfg( + name="terrain_only", + frame=ObjRef(type="body", name="base", entity="robot"), + pattern=GridPatternCfg(), + include_geom_groups=(0, 1), # Only hit geoms in groups 0 and 1 + ) + +This is useful for ignoring certain geometry (e.g., visual-only geoms in +group 3) while still detecting collisions with terrain (group 0). + + +Output Data +----------- + +Access sensor data via the ``data`` property, which returns ``RayCastData``: + +- ``distances``: [B, N] Distance to hit, or -1 if no hit / beyond max_distance +- ``hit_pos_w``: [B, N, 3] World-space hit positions +- ``normals_w``: [B, N, 3] Surface normals at hit points (world frame) +- ``pos_w``: [B, 3] Sensor frame position +- ``quat_w``: [B, 4] Sensor frame orientation (w, x, y, z) + +Where B = number of environments, N = number of rays. +""" + +from __future__ import annotations + +import math +from dataclasses import dataclass, field +from typing import TYPE_CHECKING, Literal + +import mujoco +import mujoco_warp as mjwarp +import torch +import warp as wp +from mujoco_warp import rays + +from mjlab.entity import Entity +from mjlab.sensor.builtin_sensor import ObjRef +from mjlab.sensor.sensor import Sensor, SensorCfg +from mjlab.utils.lab_api.math import quat_from_matrix + +if TYPE_CHECKING: + from mjlab.sensor.sensor_context import SensorContext + from mjlab.viewer.debug_visualizer import DebugVisualizer + + +# NOTE: Need to define this here because it's not publicly exposed by mujoco_warp. +vec6 = wp.types.vector(length=6, dtype=float) + +# Type aliases for configuration choices. +RayAlignment = Literal["base", "yaw", "world"] + + +@dataclass +class GridPatternCfg: + """Grid pattern - parallel rays in a 2D grid.""" + + size: tuple[float, float] = (1.0, 1.0) + """Grid size (length, width) in meters.""" + + resolution: float = 0.1 + """Spacing between rays in meters.""" + + direction: tuple[float, float, float] = (0.0, 0.0, -1.0) + """Ray direction in frame-local coordinates.""" + + def generate_rays( + self, mj_model: mujoco.MjModel | None, device: str + ) -> tuple[torch.Tensor, torch.Tensor]: + """Generate ray pattern. + + Args: + mj_model: MuJoCo model (unused for grid pattern). + device: Device for tensor operations. + + Returns: + Tuple of (local_offsets [N, 3], local_directions [N, 3]). + """ + del mj_model # Unused for grid pattern + size_x, size_y = self.size + res = self.resolution + + x = torch.arange( + -size_x / 2, size_x / 2 + res * 0.5, res, device=device, dtype=torch.float32 + ) + y = torch.arange( + -size_y / 2, size_y / 2 + res * 0.5, res, device=device, dtype=torch.float32 + ) + grid_x, grid_y = torch.meshgrid(x, y, indexing="xy") + + num_rays = grid_x.numel() + local_offsets = torch.zeros((num_rays, 3), device=device, dtype=torch.float32) + local_offsets[:, 0] = grid_x.flatten() + local_offsets[:, 1] = grid_y.flatten() + + # All rays share the same direction for grid pattern. + direction = torch.tensor(self.direction, device=device, dtype=torch.float32) + direction = direction / direction.norm() + local_directions = direction.unsqueeze(0).expand(num_rays, 3).clone() + + return local_offsets, local_directions + + +@dataclass +class PinholeCameraPatternCfg: + """Pinhole camera pattern - rays diverging from origin like a camera. + + Can be configured with explicit parameters (width, height, fovy) or created + via factory methods like from_mujoco_camera() or from_intrinsic_matrix(). + """ + + width: int = 16 + """Image width in pixels.""" + + height: int = 12 + """Image height in pixels.""" + + fovy: float = 45.0 + """Vertical field of view in degrees (matches MuJoCo convention).""" + + _camera_name: str | None = field(default=None, repr=False) + """Internal: MuJoCo camera name for deferred parameter resolution.""" + + @classmethod + def from_mujoco_camera(cls, camera_name: str) -> PinholeCameraPatternCfg: + """Create config that references a MuJoCo camera. + + Camera parameters (resolution, FOV) are resolved at runtime from the model. + + Args: + camera_name: Name of the MuJoCo camera to reference. + + Returns: + Config that will resolve parameters from the MuJoCo camera. + """ + # Placeholder values; actual values resolved in generate_rays(). + return cls(width=0, height=0, fovy=0.0, _camera_name=camera_name) + + @classmethod + def from_intrinsic_matrix( + cls, intrinsic_matrix: list[float], width: int, height: int + ) -> PinholeCameraPatternCfg: + """Create from 3x3 intrinsic matrix [fx, 0, cx, 0, fy, cy, 0, 0, 1]. + + Args: + intrinsic_matrix: Flattened 3x3 intrinsic matrix. + width: Image width in pixels. + height: Image height in pixels. + + Returns: + Config with fovy computed from the intrinsic matrix. + """ + fy = intrinsic_matrix[4] # fy is at position [1,1] in the matrix + fovy = 2 * math.atan(height / (2 * fy)) * 180 / math.pi + return cls(width=width, height=height, fovy=fovy) + + def generate_rays( + self, mj_model: mujoco.MjModel | None, device: str + ) -> tuple[torch.Tensor, torch.Tensor]: + """Generate ray pattern. + + Args: + mj_model: MuJoCo model (required if using from_mujoco_camera). + device: Device for tensor operations. + + Returns: + Tuple of (local_offsets [N, 3], local_directions [N, 3]). + """ + # Resolve camera parameters. + if self._camera_name is not None: + if mj_model is None: + raise ValueError("MuJoCo model required when using from_mujoco_camera()") + # Get parameters from MuJoCo camera. + cam_id = mj_model.camera(self._camera_name).id + width, height = mj_model.cam_resolution[cam_id] + + # MuJoCo has two camera modes: + # 1. fovy mode: sensorsize is zero, use cam_fovy directly + # 2. Physical sensor mode: sensorsize > 0, compute from focal/sensorsize + sensorsize = mj_model.cam_sensorsize[cam_id] + if sensorsize[0] > 0 and sensorsize[1] > 0: + # Physical sensor model. + intrinsic = mj_model.cam_intrinsic[cam_id] # [fx, fy, cx, cy] + focal = intrinsic[:2] # [fx, fy] + h_fov_rad = 2 * math.atan(sensorsize[0] / (2 * focal[0])) + v_fov_rad = 2 * math.atan(sensorsize[1] / (2 * focal[1])) + else: + # Read vertical FOV directly from MuJoCo. + v_fov_rad = math.radians(mj_model.cam_fovy[cam_id]) + aspect = width / height + h_fov_rad = 2 * math.atan(math.tan(v_fov_rad / 2) * aspect) + else: + # Use explicit parameters. + width = self.width + height = self.height + v_fov_rad = math.radians(self.fovy) + aspect = width / height + h_fov_rad = 2 * math.atan(math.tan(v_fov_rad / 2) * aspect) + + # Create normalized pixel coordinates [-1, 1]. + u = torch.linspace(-1, 1, width, device=device, dtype=torch.float32) + v = torch.linspace(-1, 1, height, device=device, dtype=torch.float32) + grid_u, grid_v = torch.meshgrid(u, v, indexing="xy") + + # Convert to ray directions (MuJoCo camera: -Z forward, +X right, +Y down). + ray_x = grid_u.flatten() * math.tan(h_fov_rad / 2) + ray_y = grid_v.flatten() * math.tan(v_fov_rad / 2) + ray_z = -torch.ones_like(ray_x) # Negative Z for MuJoCo camera forward + + num_rays = width * height + local_offsets = torch.zeros((num_rays, 3), device=device) + local_directions = torch.stack([ray_x, ray_y, ray_z], dim=1) + local_directions = local_directions / local_directions.norm(dim=1, keepdim=True) + + return local_offsets, local_directions + + +PatternCfg = GridPatternCfg | PinholeCameraPatternCfg + + +@dataclass +class RayCastData: + """Raycast sensor output data. + + Note: + Fields are views into GPU buffers and are valid until the next + ``sense()`` call. + """ + + distances: torch.Tensor + """[B, N] Distance to hit point. -1 if no hit.""" + + normals_w: torch.Tensor + """[B, N, 3] Surface normal at hit point (world frame). Zero if no hit.""" + + hit_pos_w: torch.Tensor + """[B, N, 3] Hit position in world frame. Ray origin if no hit.""" + + pos_w: torch.Tensor + """[B, 3] Frame position in world coordinates.""" + + quat_w: torch.Tensor + """[B, 4] Frame orientation quaternion (w, x, y, z) in world coordinates.""" + + +@dataclass +class RayCastSensorCfg(SensorCfg): + """Raycast sensor configuration. + + Supports multiple ray patterns (grid, pinhole camera) and alignment modes. + """ + + @dataclass + class VizCfg: + """Visualization settings for debug rendering.""" + + hit_color: tuple[float, float, float, float] = (0.0, 1.0, 0.0, 0.8) + """RGBA color for rays that hit a surface.""" + + miss_color: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.4) + """RGBA color for rays that miss.""" + + hit_sphere_color: tuple[float, float, float, float] = (0.0, 1.0, 1.0, 1.0) + """RGBA color for spheres drawn at hit points.""" + + hit_sphere_radius: float = 0.5 + """Radius of spheres drawn at hit points (multiplier of meansize).""" + + show_rays: bool = False + """Whether to draw ray arrows.""" + + show_normals: bool = False + """Whether to draw surface normals at hit points.""" + + normal_color: tuple[float, float, float, float] = (1.0, 1.0, 0.0, 1.0) + """RGBA color for surface normal arrows.""" + + normal_length: float = 5.0 + """Length of surface normal arrows (multiplier of meansize).""" + + frame: ObjRef + """Body or site to attach rays to.""" + + pattern: PatternCfg = field(default_factory=GridPatternCfg) + """Ray pattern configuration. Defaults to GridPatternCfg.""" + + ray_alignment: RayAlignment = "base" + """How rays align with the frame. + + - "base": Full position + rotation (default). + - "yaw": Position + yaw only, ignores pitch/roll (good for height maps). + - "world": Fixed in world frame, position only follows body. + """ + + max_distance: float = 10.0 + """Maximum ray distance. Rays beyond this report -1.""" + + exclude_parent_body: bool = True + """Exclude parent body from ray intersection tests.""" + + include_geom_groups: tuple[int, ...] | None = (0, 1, 2) + """Geom groups (0-5) to include in raycasting. + + Defaults to (0, 1, 2). Set to None to include all groups. + """ + + debug_vis: bool = False + """Enable debug visualization.""" + + viz: VizCfg = field(default_factory=VizCfg) + """Visualization settings.""" + + def build(self) -> RayCastSensor: + return RayCastSensor(self) + + +class RayCastSensor(Sensor[RayCastData]): + """Raycast sensor for terrain and obstacle detection.""" + + requires_sensor_context = True + + def __init__(self, cfg: RayCastSensorCfg) -> None: + super().__init__() + self.cfg = cfg + self._data: mjwarp.Data | None = None + self._model: mjwarp.Model | None = None + self._mj_model: mujoco.MjModel | None = None + self._device: str | None = None + self._wp_device: wp.context.Device | None = None + + self._frame_body_id: int | None = None + self._frame_site_id: int | None = None + self._frame_geom_id: int | None = None + self._frame_type: Literal["body", "site", "geom"] = "body" + + self._local_offsets: torch.Tensor | None = None + self._local_directions: torch.Tensor | None = None # [N, 3] per-ray directions + self._num_rays: int = 0 + + self._ray_pnt: wp.array | None = None + self._ray_vec: wp.array | None = None + self._ray_dist: wp.array | None = None + self._ray_geomid: wp.array | None = None + self._ray_normal: wp.array | None = None + self._ray_bodyexclude: wp.array | None = None + self._geomgroup = vec6(-1, -1, -1, -1, -1, -1) + + self._distances: torch.Tensor | None = None + self._normals_w: torch.Tensor | None = None + self._hit_pos_w: torch.Tensor | None = None + self._pos_w: torch.Tensor | None = None + self._quat_w: torch.Tensor | None = None + + self._cached_world_origins: torch.Tensor | None = None + self._cached_world_rays: torch.Tensor | None = None + self._cached_frame_pos: torch.Tensor | None = None + self._cached_frame_mat: torch.Tensor | None = None + + self._ctx: SensorContext | None = None + + def edit_spec( + self, + scene_spec: mujoco.MjSpec, + entities: dict[str, Entity], + ) -> None: + del scene_spec, entities + + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + self._data = data + self._model = model + self._mj_model = mj_model + self._device = device + self._wp_device = wp.get_device(device) + num_envs = data.nworld + + frame = self.cfg.frame + frame_name = frame.prefixed_name() + + if frame.type == "body": + self._frame_body_id = mj_model.body(frame_name).id + self._frame_type = "body" + elif frame.type == "site": + self._frame_site_id = mj_model.site(frame_name).id + # Look up parent body for exclusion. + self._frame_body_id = int(mj_model.site_bodyid[self._frame_site_id]) + self._frame_type = "site" + elif frame.type == "geom": + self._frame_geom_id = mj_model.geom(frame_name).id + # Look up parent body for exclusion. + self._frame_body_id = int(mj_model.geom_bodyid[self._frame_geom_id]) + self._frame_type = "geom" + else: + raise ValueError( + f"RayCastSensor frame must be 'body', 'site', or 'geom', got '{frame.type}'" + ) + + # Generate ray pattern. + pattern = self.cfg.pattern + self._local_offsets, self._local_directions = pattern.generate_rays( + mj_model, device + ) + self._num_rays = self._local_offsets.shape[0] + + self._ray_pnt = wp.zeros((num_envs, self._num_rays), dtype=wp.vec3, device=device) + self._ray_vec = wp.zeros((num_envs, self._num_rays), dtype=wp.vec3, device=device) + self._ray_dist = wp.zeros((num_envs, self._num_rays), dtype=float, device=device) + self._ray_geomid = wp.zeros((num_envs, self._num_rays), dtype=int, device=device) + self._ray_normal = wp.zeros( + (num_envs, self._num_rays), dtype=wp.vec3, device=device + ) + + body_exclude = ( + self._frame_body_id + if self.cfg.exclude_parent_body and self._frame_body_id is not None + else -1 + ) + self._ray_bodyexclude = wp.full( + (self._num_rays,), + body_exclude, + dtype=int, # pyright: ignore[reportArgumentType] + device=device, + ) + + # Convert include_geom_groups to vec6 format (-1 = include, 0 = exclude). + if self.cfg.include_geom_groups is not None: + groups = [0, 0, 0, 0, 0, 0] + for g in self.cfg.include_geom_groups: + if 0 <= g <= 5: + groups[g] = -1 + self._geomgroup = vec6(*groups) + else: + self._geomgroup = vec6(-1, -1, -1, -1, -1, -1) # All groups + + # Pre-allocate output tensors so shape inference works before + # the first sense() call. + self._distances = torch.zeros(num_envs, self._num_rays, device=device) + self._normals_w = torch.zeros(num_envs, self._num_rays, 3, device=device) + self._hit_pos_w = torch.zeros(num_envs, self._num_rays, 3, device=device) + self._pos_w = torch.zeros(num_envs, 3, device=device) + self._quat_w = torch.zeros(num_envs, 4, device=device) + + assert self._wp_device is not None + + def set_context(self, ctx: SensorContext) -> None: + """Wire this sensor to a SensorContext for BVH-accelerated raycasting.""" + self._ctx = ctx + + def _compute_data(self) -> RayCastData: + if self._ctx is None: + raise RuntimeError( + "RayCastSensor requires a SensorContext. " + "Ensure the sensor is part of a scene with " + "sim.sense() calls." + ) + assert self._distances is not None and self._normals_w is not None + assert self._hit_pos_w is not None + assert self._pos_w is not None and self._quat_w is not None + return RayCastData( + distances=self._distances, + normals_w=self._normals_w, + hit_pos_w=self._hit_pos_w, + pos_w=self._pos_w, + quat_w=self._quat_w, + ) + + @property + def num_rays(self) -> int: + return self._num_rays + + def debug_vis(self, visualizer: DebugVisualizer) -> None: + if not self.cfg.debug_vis: + return + assert self._data is not None + assert self._local_offsets is not None + assert self._local_directions is not None + + data = self.data + env_indices = list(visualizer.get_env_indices(data.distances.shape[0])) + if not env_indices: + return + + # Gather frame poses for selected environments only. + if self._frame_type == "body": + frame_pos = self._data.xpos[env_indices, self._frame_body_id] + frame_mat = self._data.xmat[env_indices, self._frame_body_id] + elif self._frame_type == "site": + frame_pos = self._data.site_xpos[env_indices, self._frame_site_id] + frame_mat = self._data.site_xmat[env_indices, self._frame_site_id] + else: # geom + frame_pos = self._data.geom_xpos[env_indices, self._frame_geom_id] + frame_mat = self._data.geom_xmat[env_indices, self._frame_geom_id] + + rot_mats = self._compute_alignment_rotation(frame_mat.view(-1, 3, 3)).cpu().numpy() + origins = frame_pos.cpu().numpy() + offsets = self._local_offsets.cpu().numpy() + directions = self._local_directions.cpu().numpy() + hit_positions = data.hit_pos_w[env_indices].cpu().numpy() + distances = data.distances[env_indices].cpu().numpy() + normals = data.normals_w[env_indices].cpu().numpy() + + meansize = visualizer.meansize + ray_width = 0.1 * meansize + sphere_radius = self.cfg.viz.hit_sphere_radius * meansize + normal_length = self.cfg.viz.normal_length * meansize + normal_width = 0.1 * meansize + miss_extent = min(0.5, self.cfg.max_distance * 0.05) + name = self.cfg.name + + for k in range(len(env_indices)): + rot = rot_mats[k] + + for i in range(self._num_rays): + origin = origins[k] + rot @ offsets[i] + hit = distances[k, i] >= 0 + + if hit: + end = hit_positions[k, i] + color = self.cfg.viz.hit_color + else: + end = origin + rot @ directions[i] * miss_extent + color = self.cfg.viz.miss_color + + if self.cfg.viz.show_rays: + visualizer.add_arrow( + start=origin, + end=end, + color=color, + width=ray_width, + label=f"{name}_ray_{i}", + ) + + if hit: + visualizer.add_sphere( + center=end, + radius=sphere_radius, + color=self.cfg.viz.hit_sphere_color, + label=f"{name}_hit_{i}", + ) + if self.cfg.viz.show_normals: + normal_end = end + normals[k, i] * normal_length + visualizer.add_arrow( + start=end, + end=normal_end, + color=self.cfg.viz.normal_color, + width=normal_width, + label=f"{name}_normal_{i}", + ) + + # Private methods. + + def prepare_rays(self) -> None: + """PRE-GRAPH: Transform local rays to world frame. + + Reads body/site/geom poses via PyTorch and writes world-frame ray + origins and directions into Warp arrays. Caches the frame pose and + world-frame tensors for postprocess_rays(). + """ + assert self._data is not None and self._model is not None + assert self._local_offsets is not None and self._local_directions is not None + + if self._frame_type == "body": + frame_pos = self._data.xpos[:, self._frame_body_id] + frame_mat = self._data.xmat[:, self._frame_body_id].view(-1, 3, 3) + elif self._frame_type == "site": + frame_pos = self._data.site_xpos[:, self._frame_site_id] + frame_mat = self._data.site_xmat[:, self._frame_site_id].view(-1, 3, 3) + else: # geom + frame_pos = self._data.geom_xpos[:, self._frame_geom_id] + frame_mat = self._data.geom_xmat[:, self._frame_geom_id].view(-1, 3, 3) + + num_envs = frame_pos.shape[0] + rot_mat = self._compute_alignment_rotation(frame_mat) + + world_offsets = torch.einsum("bij,nj->bni", rot_mat, self._local_offsets) + world_origins = frame_pos.unsqueeze(1) + world_offsets + world_rays = torch.einsum("bij,nj->bni", rot_mat, self._local_directions) + + assert self._ray_pnt is not None and self._ray_vec is not None + pnt_torch = wp.to_torch(self._ray_pnt).view(num_envs, self._num_rays, 3) + vec_torch = wp.to_torch(self._ray_vec).view(num_envs, self._num_rays, 3) + pnt_torch.copy_(world_origins) + vec_torch.copy_(world_rays) + + # Cache for postprocess_rays(). + self._cached_world_origins = world_origins + self._cached_world_rays = world_rays + self._cached_frame_pos = frame_pos + self._cached_frame_mat = frame_mat + + def raycast_kernel(self, rc: mjwarp.RenderContext) -> None: + """IN-GRAPH: Execute BVH-accelerated raycast kernel.""" + rays( + m=self._model.struct, # type: ignore[attr-defined] + d=self._data.struct, # type: ignore[attr-defined] + pnt=self._ray_pnt, + vec=self._ray_vec, + geomgroup=self._geomgroup, # pyright: ignore[reportArgumentType] + flg_static=True, + bodyexclude=self._ray_bodyexclude, + dist=self._ray_dist, + geomid=self._ray_geomid, + normal=self._ray_normal, + rc=rc, + ) + + def postprocess_rays(self) -> None: + """POST-GRAPH: Convert Warp outputs to PyTorch, compute hit positions.""" + assert self._cached_world_origins is not None + assert self._cached_world_rays is not None + assert self._cached_frame_pos is not None + assert self._cached_frame_mat is not None + + num_envs = self._cached_frame_pos.shape[0] + + assert self._ray_dist is not None and self._ray_normal is not None + self._distances = wp.to_torch(self._ray_dist) + self._normals_w = wp.to_torch(self._ray_normal).view(num_envs, self._num_rays, 3) + self._distances[self._distances > self.cfg.max_distance] = -1.0 + + hit_mask = self._distances >= 0 + hit_pos_w = self._cached_world_origins.clone() + hit_pos_w[hit_mask] = self._cached_world_origins[ + hit_mask + ] + self._cached_world_rays[hit_mask] * self._distances[hit_mask].unsqueeze(-1) + self._hit_pos_w = hit_pos_w + + # Zero out normals for misses. + self._normals_w[~hit_mask] = 0.0 + + self._pos_w = self._cached_frame_pos.clone() + self._quat_w = quat_from_matrix(self._cached_frame_mat) + + def _compute_alignment_rotation(self, frame_mat: torch.Tensor) -> torch.Tensor: + """Compute rotation matrix based on ray_alignment setting.""" + if self.cfg.ray_alignment == "base": + # Full rotation. + return frame_mat + elif self.cfg.ray_alignment == "yaw": + # Extract yaw only, zero out pitch/roll. + return self._extract_yaw_rotation(frame_mat) + elif self.cfg.ray_alignment == "world": + # Identity rotation (world-aligned). + num_envs = frame_mat.shape[0] + return ( + torch.eye(3, device=frame_mat.device, dtype=frame_mat.dtype) + .unsqueeze(0) + .expand(num_envs, -1, -1) + ) + else: + raise ValueError(f"Unknown ray_alignment: {self.cfg.ray_alignment}") + + def _extract_yaw_rotation(self, rot_mat: torch.Tensor) -> torch.Tensor: + """Extract yaw-only rotation matrix (rotation around Z axis). + + Handles the singularity at ±90° pitch by falling back to the Y-axis + when the X-axis projection onto the XY plane is too small. + """ + batch_size = rot_mat.shape[0] + device = rot_mat.device + dtype = rot_mat.dtype + + # Project X-axis onto XY plane. + x_axis = rot_mat[:, :, 0] # First column [B, 3] + x_proj = x_axis.clone() + x_proj[:, 2] = 0 # Zero out Z component + x_norm = x_proj.norm(dim=1) # [B] + + # Check for singularity (X-axis nearly vertical). + threshold = 0.1 + singular = x_norm < threshold # [B] + + # For singular cases, use Y-axis instead. + if singular.any(): + y_axis = rot_mat[:, :, 1] # Second column [B, 3] + y_proj = y_axis.clone() + y_proj[:, 2] = 0 + y_norm = y_proj.norm(dim=1).clamp(min=1e-6) + y_proj = y_proj / y_norm.unsqueeze(-1) + # Y-axis points left; rotate -90° around Z to get forward direction. + # [y_x, y_y] -> [y_y, -y_x] + x_from_y = torch.zeros_like(y_proj) + x_from_y[:, 0] = y_proj[:, 1] + x_from_y[:, 1] = -y_proj[:, 0] + x_proj[singular] = x_from_y[singular] + x_norm[singular] = 1.0 # Already normalized + + # Normalize X projection. + x_norm = x_norm.clamp(min=1e-6) + x_proj = x_proj / x_norm.unsqueeze(-1) + + # Build yaw-only rotation matrix. + yaw_mat = torch.zeros((batch_size, 3, 3), device=device, dtype=dtype) + yaw_mat[:, 0, 0] = x_proj[:, 0] + yaw_mat[:, 1, 0] = x_proj[:, 1] + yaw_mat[:, 0, 1] = -x_proj[:, 1] + yaw_mat[:, 1, 1] = x_proj[:, 0] + yaw_mat[:, 2, 2] = 1 + return yaw_mat diff --git a/mjlab/src/mjlab/sensor/sensor.py b/mjlab/src/mjlab/sensor/sensor.py new file mode 100644 index 0000000000000000000000000000000000000000..8024c322b831508eac122b3df1d57d0aef2049eb --- /dev/null +++ b/mjlab/src/mjlab/sensor/sensor.py @@ -0,0 +1,157 @@ +"""Base sensor interface.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from dataclasses import dataclass +from typing import TYPE_CHECKING, Any, Generic, TypeVar + +import mujoco +import mujoco_warp as mjwarp +import torch + +if TYPE_CHECKING: + from mjlab.entity import Entity + from mjlab.viewer.debug_visualizer import DebugVisualizer + + +T = TypeVar("T") + + +@dataclass +class SensorCfg(ABC): + """Base configuration for a sensor.""" + + name: str + + @abstractmethod + def build(self) -> Sensor[Any]: + """Build sensor instance from this config.""" + raise NotImplementedError + + +class Sensor(ABC, Generic[T]): + """Base sensor interface with typed data and per-step caching. + + Type parameter T specifies the type of data returned by the sensor. For example: + - Sensor[torch.Tensor] for sensors returning raw tensors + - Sensor[ContactData] for sensors returning structured contact data + + Subclasses should not forget to: + - Call `super().__init__()` in their `__init__` method + - If overriding `reset()` or `update()`, call `super()` FIRST to invalidate cache + """ + + requires_sensor_context: bool = False + """Whether this sensor needs a SensorContext (render context).""" + + def __init__(self) -> None: + self._cached_data: T | None = None + self._cache_valid: bool = False + + @abstractmethod + def edit_spec( + self, + scene_spec: mujoco.MjSpec, + entities: dict[str, Entity], + ) -> None: + """Edit the scene spec to add this sensor. + + This is called during scene construction to add sensor elements + to the MjSpec. + + Args: + scene_spec: The scene MjSpec to edit. + entities: Dictionary of entities in the scene, keyed by name. + """ + raise NotImplementedError + + @abstractmethod + def initialize( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + device: str, + ) -> None: + """Initialize the sensor after model compilation. + + This is called after the MjSpec is compiled into an MjModel and the simulation + is ready to run. Use this to cache sensor indices, allocate buffers, etc. + + Args: + mj_model: The compiled MuJoCo model. + model: The mjwarp model wrapper. + data: The mjwarp data arrays. + device: Device for tensor operations (e.g., "cuda", "cpu"). + """ + raise NotImplementedError + + @property + def data(self) -> T: + """Get the current sensor data, using cached value if available. + + This property returns the sensor's current data in its specific type. + The data type is specified by the type parameter T. The data is cached + per-step and recomputed only when the cache is invalidated (after + `reset()` or `update()` is called). + + Returns: + The sensor data in the format specified by type parameter T. + """ + if not self._cache_valid: + self._cached_data = self._compute_data() + self._cache_valid = True + assert self._cached_data is not None + return self._cached_data + + @abstractmethod + def _compute_data(self) -> T: + """Compute and return the sensor data. + + Subclasses must implement this method to compute the sensor's data. + This is called by the `data` property when the cache is invalid. + + Returns: + The computed sensor data. + """ + raise NotImplementedError + + def _invalidate_cache(self) -> None: + """Invalidate the cached data, forcing recomputation on next access.""" + self._cache_valid = False + + def reset(self, env_ids: torch.Tensor | slice | None = None) -> None: + """Reset sensor state for specified environments. + + Invalidates the data cache. Override in subclasses that maintain + internal state, but call `super().reset(env_ids)` FIRST. + + Args: + env_ids: Environment indices to reset. If None, reset all environments. + """ + del env_ids # Unused. + self._invalidate_cache() + + def update(self, dt: float) -> None: + """Update sensor state after a simulation step. + + Invalidates the data cache. Override in subclasses that need + per-step updates, but call `super().update(dt)` FIRST. + + Args: + dt: Time step in seconds. + """ + del dt # Unused. + self._invalidate_cache() + + def debug_vis(self, visualizer: DebugVisualizer) -> None: + """Visualize sensor data for debugging. + + Base implementation does nothing. Override in subclasses that support + debug visualization. + + Args: + visualizer: The debug visualizer to draw to. + """ + del visualizer # Unused. diff --git a/mjlab/src/mjlab/sensor/sensor_context.py b/mjlab/src/mjlab/sensor/sensor_context.py new file mode 100644 index 0000000000000000000000000000000000000000..10bc42082905894d6a044f47c95f3b1d48e1e2ee --- /dev/null +++ b/mjlab/src/mjlab/sensor/sensor_context.py @@ -0,0 +1,320 @@ +"""Shared render context for camera and raycast sensors.""" + +from __future__ import annotations + +import warnings +from typing import TYPE_CHECKING + +import mujoco +import mujoco_warp as mjwarp +import torch +import warp as wp + +if TYPE_CHECKING: + from mjlab.sensor.camera_sensor import CameraSensor + from mjlab.sensor.raycast_sensor import RayCastSensor + + +@wp.kernel +def _unpack_rgb_kernel( + packed: wp.array2d(dtype=wp.uint32), # type: ignore[valid-type] + rgb: wp.array3d(dtype=wp.uint8), # type: ignore[valid-type] +): + """Unpack ABGR uint32 pixels into separate R, G, B uint8 channels.""" + world_idx, pixel_idx = wp.tid() # type: ignore[attr-defined] + val = packed[world_idx, pixel_idx] + b = wp.uint8(val & wp.uint32(0xFF)) + g = wp.uint8((val >> wp.uint32(8)) & wp.uint32(0xFF)) + r = wp.uint8((val >> wp.uint32(16)) & wp.uint32(0xFF)) + rgb[world_idx, pixel_idx, 0] = r + rgb[world_idx, pixel_idx, 1] = g + rgb[world_idx, pixel_idx, 2] = b + + +class SensorContext: + """Container for shared sensing resources. + + Manages the RenderContext used by both camera sensors (for rendering) and raycast + sensors (for BVH-accelerated ray intersection). The actual graph capture and + execution is handled by Simulation. + """ + + def __init__( + self, + mj_model: mujoco.MjModel, + model: mjwarp.Model, + data: mjwarp.Data, + camera_sensors: list[CameraSensor], + raycast_sensors: list[RayCastSensor], + device: str, + ): + self._model = model + self._data = data + self.wp_device = wp.get_device(device) + + # Sort camera sensors by camera index for consistent ordering. + self.camera_sensors = sorted(camera_sensors, key=lambda s: s.camera_idx) + self.raycast_sensors = raycast_sensors + + # MuJoCo camera ID -> sorted list index. + self._cam_idx_to_list_idx = { + s.camera_idx: idx for idx, s in enumerate(self.camera_sensors) + } + + if self.camera_sensors: + self._validate_sensor_settings() + + self._rgb_unpacked: wp.array | None = None + self._rgb_torch: torch.Tensor | None = None + self._depth_torch: torch.Tensor | None = None + self._rgb_adr_np: list[int] | None = None + self._depth_adr_np: list[int] | None = None + self._create_context(mj_model) + + # Wire up sensors to use this context. + for sensor in self.camera_sensors: + sensor.set_context(self) + for sensor in self.raycast_sensors: + sensor.set_context(self) + + @property + def has_cameras(self) -> bool: + return len(self.camera_sensors) > 0 + + @property + def has_raycasts(self) -> bool: + return len(self.raycast_sensors) > 0 + + @property + def render_context(self) -> mjwarp.RenderContext: + return self._ctx + + def recreate(self, mj_model: mujoco.MjModel) -> None: + """Recreate the render context after model fields are expanded. + + Called by Simulation.expand_model_fields() for domain randomization. + """ + self._create_context(mj_model) + + def prepare(self) -> None: + """Pre-graph: transform rays to world frame.""" + for sensor in self.raycast_sensors: + sensor.prepare_rays() + + def finalize(self) -> None: + """Post-graph: compute raycast hit positions.""" + for sensor in self.raycast_sensors: + sensor.postprocess_rays() + + def get_rgb(self, cam_idx: int) -> torch.Tensor: + """Get unpacked RGB data for a camera. + + Args: + cam_idx: MuJoCo camera ID. + + Returns: + Tensor of shape [num_envs, height, width, 3] (uint8). + """ + if self._rgb_unpacked is None: + raise RuntimeError( + "RGB rendering is not enabled. Ensure at least one camera sensor has 'rgb' in" + " its data_types." + ) + + if cam_idx not in self._cam_idx_to_list_idx: + available = list(self._cam_idx_to_list_idx.keys()) + raise KeyError( + f"Camera ID {cam_idx} not found in SensorContext. " + f"Available camera IDs: {available}" + ) + + list_idx = self._cam_idx_to_list_idx[cam_idx] + + assert self._rgb_adr_np is not None + assert self._rgb_torch is not None + rgb_adr = self._rgb_adr_np[list_idx] + if rgb_adr < 0: + raise RuntimeError(f"Camera ID {cam_idx} does not have RGB rendering enabled.") + + sensor = self.camera_sensors[list_idx] + w, h = sensor.cfg.width, sensor.cfg.height + num_pixels = w * h + nworld = self._data.nworld + + cam_data = self._rgb_torch[:, rgb_adr : rgb_adr + num_pixels, :] + return cam_data.view(nworld, h, w, 3) + + def get_depth(self, cam_idx: int) -> torch.Tensor: + """Get depth data for a camera. + + Args: + cam_idx: MuJoCo camera ID. + + Returns: + Tensor of shape [num_envs, height, width, 1] (float32). + """ + if cam_idx not in self._cam_idx_to_list_idx: + available = list(self._cam_idx_to_list_idx.keys()) + raise KeyError( + f"Camera ID {cam_idx} not found in SensorContext. " + f"Available camera IDs: {available}" + ) + + list_idx = self._cam_idx_to_list_idx[cam_idx] + + assert self._depth_adr_np is not None + assert self._depth_torch is not None + depth_adr = self._depth_adr_np[list_idx] + if depth_adr < 0: + raise RuntimeError(f"Camera ID {cam_idx} does not have depth rendering enabled.") + + sensor = self.camera_sensors[list_idx] + w, h = sensor.cfg.width, sensor.cfg.height + num_pixels = w * h + nworld = self._data.nworld + + cam_data = self._depth_torch[:, depth_adr : depth_adr + num_pixels] + return cam_data.view(nworld, h, w, 1) + + # Private methods. + + def _validate_sensor_settings(self) -> None: + """Validate that all camera sensors share render settings.""" + ref = self.camera_sensors[0].cfg + for s in self.camera_sensors[1:]: + cfg = s.cfg + if cfg.use_textures != ref.use_textures: + raise ValueError( + "All camera sensors must share the same use_textures " + f"setting. '{s.cfg.name}' differs from " + f"'{ref.name}'." + ) + if cfg.use_shadows != ref.use_shadows: + raise ValueError( + "All camera sensors must share the same use_shadows " + f"setting. '{s.cfg.name}' differs from " + f"'{ref.name}'." + ) + if cfg.enabled_geom_groups != ref.enabled_geom_groups: + raise ValueError( + "All camera sensors must share the same " + f"enabled_geom_groups. '{s.cfg.name}' differs from " + f"'{ref.name}'." + ) + + def _raycast_geom_groups(self) -> set[int]: + """Compute the union of geom groups across all raycast sensors.""" + groups: set[int] = set() + for s in self.raycast_sensors: + if s.cfg.include_geom_groups is None: + return {0, 1, 2, 3, 4, 5} + groups.update(s.cfg.include_geom_groups) + return groups + + def _create_context(self, mj_model: mujoco.MjModel) -> None: + """Create the mujoco_warp RenderContext.""" + ncam = mj_model.ncam + cam_res: list[tuple[int, int]] | None = None + render_rgb: list[bool] | None = None + render_depth: list[bool] | None = None + + raycast_geom_groups = self._raycast_geom_groups() + + if self.camera_sensors: + ref_cfg = self.camera_sensors[0].cfg + use_textures = ref_cfg.use_textures + use_shadows = ref_cfg.use_shadows + cam_geom_groups = set(ref_cfg.enabled_geom_groups) + + if self.raycast_sensors and raycast_geom_groups != cam_geom_groups: + merged = sorted(cam_geom_groups | raycast_geom_groups) + warnings.warn( + "Camera enabled_geom_groups " + f"{sorted(cam_geom_groups)} and raycast " + f"include_geom_groups {sorted(raycast_geom_groups)}" + f" differ. Using union {merged}.", + stacklevel=2, + ) + enabled_geom_groups = merged + else: + enabled_geom_groups = sorted(cam_geom_groups) + + # Build cam_active mask: only activate cameras that are sensors. + # cam_res, render_rgb, render_depth follow sorted sensor order (by camera_idx). + # This must match the order used by create_render_context for rgb_adr/depth_adr + # indexing. + cam_active = [False] * ncam + cam_res = [] + render_rgb = [] + render_depth = [] + + for s in self.camera_sensors: + cam_active[s.camera_idx] = True + cam_res.append((s.cfg.width, s.cfg.height)) + render_rgb.append("rgb" in s.cfg.data_types) + render_depth.append("depth" in s.cfg.data_types) + else: + # Raycasts-only: need BVH but no camera rendering. + use_textures = False + use_shadows = False + enabled_geom_groups = sorted(raycast_geom_groups) + cam_active = [False] * ncam + + with wp.ScopedDevice(self.wp_device): + self._ctx = mjwarp.create_render_context( + mjm=mj_model, + nworld=self._data.nworld, + cam_res=cam_res, + render_rgb=render_rgb, + render_depth=render_depth, + use_textures=use_textures, + use_shadows=use_shadows, + enabled_geom_groups=enabled_geom_groups, + cam_active=cam_active, + ) + + # Cache address arrays from the render context. An adr value of -1 means that data + # type is not enabled for that camera. + if self.camera_sensors: + self._rgb_adr_np = self._ctx.rgb_adr.numpy().tolist() + self._depth_adr_np = self._ctx.depth_adr.numpy().tolist() + + has_any_rgb = self._rgb_adr_np is not None and any(a >= 0 for a in self._rgb_adr_np) + has_any_depth = self._depth_adr_np is not None and any( + a >= 0 for a in self._depth_adr_np + ) + + # Allocate RGB unpack buffer if any camera wants RGB. + if has_any_rgb: + total_rgb_pixels = self._ctx.rgb_data.shape[1] + nworld = self._data.nworld + self._rgb_unpacked = wp.zeros( + (nworld, total_rgb_pixels, 3), + dtype=wp.uint8, + device=self.wp_device, + ) + self._rgb_torch = wp.to_torch(self._rgb_unpacked) + else: + self._rgb_unpacked = None + self._rgb_torch = None + + # Cache depth torch view (zero-copy). + if has_any_depth: + self._depth_torch = wp.to_torch(self._ctx.depth_data) + else: + self._depth_torch = None + + def unpack_rgb(self) -> None: + """Unpack packed uint32 RGB data into separate channels. + + Called from Simulation._sense_kernel() so it gets captured in the + CUDA graph. No-op if no cameras need RGB. + """ + if self._rgb_unpacked is not None: + wp.launch( + _unpack_rgb_kernel, + dim=(self._data.nworld, self._ctx.rgb_data.shape[1]), + inputs=[self._ctx.rgb_data], + outputs=[self._rgb_unpacked], + device=self.wp_device, + ) diff --git a/mjlab/src/mjlab/sim/__init__.py b/mjlab/src/mjlab/sim/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..0329e1efba6030fc565b649f8ecfbf4508bb9a9a --- /dev/null +++ b/mjlab/src/mjlab/sim/__init__.py @@ -0,0 +1,5 @@ +from mjlab.sim.sim import MujocoCfg as MujocoCfg +from mjlab.sim.sim import Simulation as Simulation +from mjlab.sim.sim import SimulationCfg as SimulationCfg +from mjlab.sim.sim_data import TorchArray as TorchArray +from mjlab.sim.sim_data import WarpBridge as WarpBridge diff --git a/mjlab/src/mjlab/sim/randomization.py b/mjlab/src/mjlab/sim/randomization.py new file mode 100644 index 0000000000000000000000000000000000000000..40b1e8b89bb7dfcb0ffe40525b3432e98224c454 --- /dev/null +++ b/mjlab/src/mjlab/sim/randomization.py @@ -0,0 +1,54 @@ +from typing import Any + +import mujoco_warp as mjwarp +import warp as wp + +# Ref: https://github.com/newton-physics/newton/blob/640095cbe1914d43e9158ec71264a0eb7272fc15/newton/_src/solvers/mujoco/solver_mujoco.py#L2587-L2612 + + +@wp.kernel(module="unique") +def repeat_array_kernel( + src: wp.array(dtype=Any), # type: ignore + nelems_per_world: int, + dst: wp.array(dtype=Any), # type: ignore +): + tid = wp.tid() + src_idx = tid % nelems_per_world # type: ignore[operator] + dst[tid] = src[src_idx] + + +def expand_model_fields( + model: mjwarp.Model, + nworld: int, + fields_to_expand: list[str], +) -> None: + if nworld == 1: + return + + def tile(x: wp.array) -> wp.array: + # Create new array with same shape but first dim multiplied by nworld. + new_shape = list(x.shape) + new_shape[0] = nworld + wp_array = {1: wp.array, 2: wp.array2d, 3: wp.array3d, 4: wp.array4d}[ + len(new_shape) + ] + dst = wp_array(shape=new_shape, dtype=x.dtype, device=x.device) + + src_flat = x.flatten() + dst_flat = dst.flatten() + + # Launch kernel to repeat data, one thread per destination element. + n_elems_per_world = dst_flat.shape[0] // nworld + wp.launch( + repeat_array_kernel, + dim=dst_flat.shape[0], + inputs=[src_flat, n_elems_per_world], + outputs=[dst_flat], + device=x.device, + ) + return dst + + for field in model.__dataclass_fields__: + if field in fields_to_expand: + array = getattr(model, field) + setattr(model, field, tile(array)) diff --git a/mjlab/src/mjlab/sim/sim.py b/mjlab/src/mjlab/sim/sim.py new file mode 100644 index 0000000000000000000000000000000000000000..a28f4394be804e459ae5e973935d39791b4f361c --- /dev/null +++ b/mjlab/src/mjlab/sim/sim.py @@ -0,0 +1,374 @@ +from __future__ import annotations + +from dataclasses import dataclass, field +from typing import TYPE_CHECKING, Literal, cast + +import mujoco +import mujoco_warp as mjwarp +import torch +import warp as wp + +from mjlab.sim.randomization import expand_model_fields +from mjlab.sim.sim_data import TorchArray, WarpBridge +from mjlab.utils.nan_guard import NanGuard, NanGuardCfg + +if TYPE_CHECKING: + from mjlab.sensor.sensor_context import SensorContext + +# Type aliases for better IDE support while maintaining runtime compatibility +# At runtime, WarpBridge wraps the actual MJWarp objects. +if TYPE_CHECKING: + ModelBridge = mjwarp.Model + DataBridge = mjwarp.Data +else: + ModelBridge = WarpBridge + DataBridge = WarpBridge + +# Minimum CUDA driver version supported for conditional CUDA graphs. +_GRAPH_CAPTURE_MIN_DRIVER = (12, 4) + +_JACOBIAN_MAP = { + "auto": mujoco.mjtJacobian.mjJAC_AUTO, + "dense": mujoco.mjtJacobian.mjJAC_DENSE, + "sparse": mujoco.mjtJacobian.mjJAC_SPARSE, +} +_CONE_MAP = { + "elliptic": mujoco.mjtCone.mjCONE_ELLIPTIC, + "pyramidal": mujoco.mjtCone.mjCONE_PYRAMIDAL, +} +_INTEGRATOR_MAP = { + "euler": mujoco.mjtIntegrator.mjINT_EULER, + "implicitfast": mujoco.mjtIntegrator.mjINT_IMPLICITFAST, +} +_SOLVER_MAP = { + "newton": mujoco.mjtSolver.mjSOL_NEWTON, + "cg": mujoco.mjtSolver.mjSOL_CG, + "pgs": mujoco.mjtSolver.mjSOL_PGS, +} + + +@dataclass +class MujocoCfg: + """Configuration for MuJoCo simulation parameters.""" + + # Integrator settings. + timestep: float = 0.002 + integrator: Literal["euler", "implicitfast"] = "implicitfast" + + # Friction settings. + impratio: float = 1.0 + cone: Literal["pyramidal", "elliptic"] = "pyramidal" + + # Solver settings. + jacobian: Literal["auto", "dense", "sparse"] = "auto" + solver: Literal["newton", "cg", "pgs"] = "newton" + iterations: int = 100 + tolerance: float = 1e-8 + ls_iterations: int = 50 + ls_tolerance: float = 0.01 + ccd_iterations: int = 50 + + # Other. + gravity: tuple[float, float, float] = (0, 0, -9.81) + multiccd: bool = False + + def apply(self, model: mujoco.MjModel) -> None: + """Apply configuration settings to a compiled MjModel.""" + model.opt.jacobian = _JACOBIAN_MAP[self.jacobian] + model.opt.cone = _CONE_MAP[self.cone] + model.opt.integrator = _INTEGRATOR_MAP[self.integrator] + model.opt.solver = _SOLVER_MAP[self.solver] + model.opt.timestep = self.timestep + model.opt.impratio = self.impratio + model.opt.gravity[:] = self.gravity + model.opt.iterations = self.iterations + model.opt.tolerance = self.tolerance + model.opt.ls_iterations = self.ls_iterations + model.opt.ls_tolerance = self.ls_tolerance + model.opt.ccd_iterations = self.ccd_iterations + if self.multiccd: + model.opt.enableflags |= mujoco.mjtEnableBit.mjENBL_MULTICCD + + +@dataclass(kw_only=True) +class SimulationCfg: + nconmax: int | None = None + """Number of contacts to allocate per world. + + Contacts exist in large heterogenous arrays: one world may have more than nconmax + contacts. If None, a heuristic value is used.""" + njmax: int | None = None + """Number of constraints to allocate per world. + + Constraint arrays are batched by world: no world may have more than njmax + constraints. If None, a heuristic value is used.""" + ls_parallel: bool = True # Boosts perf quite noticeably. + contact_sensor_maxmatch: int = 64 + mujoco: MujocoCfg = field(default_factory=MujocoCfg) + nan_guard: NanGuardCfg = field(default_factory=NanGuardCfg) + + +class Simulation: + """GPU-accelerated MuJoCo simulation powered by MJWarp. + + CUDA Graph Capture + ------------------ + On CUDA devices with memory pools enabled, the simulation captures CUDA graphs + for ``step()``, ``forward()``, and ``reset()`` operations. Graph capture records + a sequence of GPU kernels and their memory addresses, then replays the entire + sequence with a single kernel launch, eliminating CPU overhead from repeated + kernel dispatches. + + **Important:** A captured graph holds pointers to the GPU arrays that existed + at capture time. If those arrays are later replaced (e.g., via + ``expand_model_fields()``), the graph will still read from the old arrays, + silently ignoring any new values. The ``expand_model_fields()`` method handles + this automatically by calling ``create_graph()`` after replacing arrays. + + If you write code that replaces model or data arrays after simulation + initialization, you **must** call ``create_graph()`` afterward to re-capture + the graphs with the new memory addresses. + """ + + def __init__( + self, num_envs: int, cfg: SimulationCfg, model: mujoco.MjModel, device: str + ): + self.cfg = cfg + self.device = device + self.wp_device = wp.get_device(self.device) + self.num_envs = num_envs + self._default_model_fields: dict[str, torch.Tensor] = {} + + # MuJoCo model and data. + self._mj_model = model + cfg.mujoco.apply(self._mj_model) + self._mj_data = mujoco.MjData(model) + mujoco.mj_forward(self._mj_model, self._mj_data) + + # MJWarp model and data. + with wp.ScopedDevice(self.wp_device): + self._wp_model = mjwarp.put_model(self._mj_model) + self._wp_model.opt.ls_parallel = cfg.ls_parallel + self._wp_model.opt.contact_sensor_maxmatch = cfg.contact_sensor_maxmatch + + self._wp_data = mjwarp.put_data( + self._mj_model, + self._mj_data, + nworld=self.num_envs, + nconmax=self.cfg.nconmax, + njmax=self.cfg.njmax, + ) + + self._reset_mask_wp = wp.zeros(num_envs, dtype=bool) + self._reset_mask = TorchArray(self._reset_mask_wp) + + self._model_bridge = WarpBridge(self._wp_model, nworld=self.num_envs) + self._data_bridge = WarpBridge(self._wp_data) + self._sensor_context: SensorContext | None = None + + self.use_cuda_graph = self._should_use_cuda_graph() + self.create_graph() + + self.nan_guard = NanGuard(cfg.nan_guard, self.num_envs, self._mj_model) + + def create_graph(self) -> None: + """Capture CUDA graphs for step, forward, and reset operations. + + This method must be called whenever GPU arrays in the model or data are + replaced after initialization. The captured graphs hold pointers to the + arrays that existed at capture time. If those arrays are replaced, the + graphs will silently read from the old arrays, ignoring any new values. + + Called automatically by: + - ``__init__()`` during simulation initialization + - ``expand_model_fields()`` after replacing model arrays + + On CPU devices or when memory pools are disabled, this is a no-op. + """ + self.step_graph = None + self.forward_graph = None + self.reset_graph = None + self.sense_graph = None + if self.use_cuda_graph: + with wp.ScopedDevice(self.wp_device): + with wp.ScopedCapture() as capture: + mjwarp.step(self.wp_model, self.wp_data) + self.step_graph = capture.graph + with wp.ScopedCapture() as capture: + mjwarp.forward(self.wp_model, self.wp_data) + self.forward_graph = capture.graph + with wp.ScopedCapture() as capture: + mjwarp.reset_data(self.wp_model, self.wp_data, reset=self._reset_mask_wp) + self.reset_graph = capture.graph + if self._sensor_context is not None: + with wp.ScopedCapture() as capture: + self._sense_kernel() + self.sense_graph = capture.graph + + # Properties. + + @property + def mj_model(self) -> mujoco.MjModel: + return self._mj_model + + @property + def mj_data(self) -> mujoco.MjData: + return self._mj_data + + @property + def wp_model(self) -> mjwarp.Model: + return self._wp_model + + @property + def wp_data(self) -> mjwarp.Data: + return self._wp_data + + @property + def data(self) -> "DataBridge": + return cast("DataBridge", self._data_bridge) + + @property + def model(self) -> "ModelBridge": + return cast("ModelBridge", self._model_bridge) + + @property + def default_model_fields(self) -> dict[str, torch.Tensor]: + """Default values for expanded model fields, used in domain randomization.""" + return self._default_model_fields + + # Methods. + + def expand_model_fields(self, fields: tuple[str, ...]) -> None: + """Expand model fields to support per-environment parameters.""" + if not fields: + return + + invalid_fields = [f for f in fields if not hasattr(self._mj_model, f)] + if invalid_fields: + raise ValueError(f"Fields not found in model: {invalid_fields}") + + expand_model_fields(self._wp_model, self.num_envs, list(fields)) + self._model_bridge.clear_cache() + + if self._sensor_context is not None: + self._sensor_context.recreate(self._mj_model) + + # Field expansion allocates new arrays and replaces them via setattr. The + # CUDA graph captured the old memory addresses, so we must recreate it. + self.create_graph() + + def get_default_field(self, field: str) -> torch.Tensor: + """Get the default value for a model field, caching for reuse. + + Returns the original values from the C MuJoCo model (mj_model), obtained + from the final compiled scene spec before any randomization is applied. + Not to be confused with the GPU Warp model (wp_model) which may have + randomized values. + """ + if field not in self._default_model_fields: + if not hasattr(self._mj_model, field): + raise ValueError(f"Field '{field}' not found in model") + model_field = getattr(self.model, field) + default_value = getattr(self._mj_model, field) + self._default_model_fields[field] = torch.as_tensor( + default_value, dtype=model_field.dtype, device=self.device + ).clone() + return self._default_model_fields[field] + + def forward(self) -> None: + with wp.ScopedDevice(self.wp_device): + if self.use_cuda_graph and self.forward_graph is not None: + wp.capture_launch(self.forward_graph) + else: + mjwarp.forward(self.wp_model, self.wp_data) + + def step(self) -> None: + with wp.ScopedDevice(self.wp_device): + with self.nan_guard.watch(self.data): + if self.use_cuda_graph and self.step_graph is not None: + wp.capture_launch(self.step_graph) + else: + mjwarp.step(self.wp_model, self.wp_data) + + def reset(self, env_ids: torch.Tensor | None = None) -> None: + with wp.ScopedDevice(self.wp_device): + if env_ids is None: + self._reset_mask.fill_(True) + else: + self._reset_mask.fill_(False) + self._reset_mask[env_ids] = True + + if self.use_cuda_graph and self.reset_graph is not None: + wp.capture_launch(self.reset_graph) + else: + mjwarp.reset_data(self.wp_model, self.wp_data, reset=self._reset_mask_wp) + + def set_sensor_context(self, ctx: SensorContext) -> None: + """Wire a SensorContext for camera/raycast sensing. + + Automatically re-captures CUDA graphs so the sense_graph includes + the new sensor kernels. + """ + self._sensor_context = ctx + self.create_graph() + + def sense(self) -> None: + """Execute the sense pipeline: prepare -> graph -> finalize. + + Runs BVH refit, camera rendering, and raycasting in a single + CUDA graph launch. Should be called once per env step, right + before observation computation. + """ + if self._sensor_context is None: + return + + ctx = self._sensor_context + ctx.prepare() + + with wp.ScopedDevice(self.wp_device): + if self.use_cuda_graph and self.sense_graph is not None: + wp.capture_launch(self.sense_graph) + else: + self._sense_kernel() + + ctx.finalize() + + # Private methods. + + def _sense_kernel(self) -> None: + """GPU kernel sequence for sensing (captured in sense_graph).""" + assert self._sensor_context is not None + ctx = self._sensor_context + rc = ctx.render_context + + mjwarp.refit_bvh(self.wp_model, self.wp_data, rc) + + if ctx.has_cameras: + mjwarp.render(self.wp_model, self.wp_data, rc) + ctx.unpack_rgb() + + for sensor in ctx.raycast_sensors: + sensor.raycast_kernel(rc=rc) + + def _should_use_cuda_graph(self) -> bool: + """Determine if CUDA graphs can be used based on device and driver version.""" + if not self.wp_device.is_cuda: + return False + + driver_ver = wp.context.runtime.driver_version + has_mempool = wp.is_mempool_enabled(self.wp_device) + + if driver_ver is None: + print("[WARNING] CUDA Graphs disabled: driver version unavailable") + return False + + if has_mempool and driver_ver >= _GRAPH_CAPTURE_MIN_DRIVER: + return True + + reasons = [] + if not has_mempool: + reasons.append("mempool disabled") + if driver_ver < _GRAPH_CAPTURE_MIN_DRIVER: + reasons.append(f"driver {driver_ver[0]}.{driver_ver[1]} < 12.4") + print(f"[WARNING] CUDA Graphs disabled: {', '.join(reasons)}") + return False diff --git a/mjlab/src/mjlab/sim/sim_data.py b/mjlab/src/mjlab/sim/sim_data.py new file mode 100644 index 0000000000000000000000000000000000000000..0f000fe5e17c18968bd0e7bfd3a09e75443751c9 --- /dev/null +++ b/mjlab/src/mjlab/sim/sim_data.py @@ -0,0 +1,246 @@ +"""Bridge for seamless PyTorch-Warp interoperability with zero-copy memory sharing. + +Provides automatic wrapping of Warp arrays as PyTorch-compatible objects while +preserving shared memory and CUDA graph compatibility. +""" + +from typing import Any, Dict, Generic, Optional, Tuple, TypeVar + +import torch +import warp as wp + +T = TypeVar("T") + + +class TorchArray: + """Warp array that behaves like a torch.Tensor with shared memory.""" + + def __init__(self, wp_array: wp.array, nworld: int | None = None) -> None: + """Initialize the tensor proxy with a Warp array.""" + self._wp_array = wp_array + # Workaround for Warp bug: wp.to_torch fails on empty CPU arrays. + if wp_array.device.is_cpu and wp_array.size == 0: # type: ignore[union-attr] + self._tensor = torch.zeros( + wp_array.shape, dtype=wp.dtype_to_torch(wp_array.dtype) + ) + else: + self._tensor = wp.to_torch(wp_array) + + if ( + nworld is not None + and nworld > 1 + and len(self._tensor.shape) > 0 + and self._tensor.stride(0) == 0 + and self._tensor.shape[0] == 1 + ): + new_shape = (nworld,) + self._tensor.shape[1:] + self._tensor = self._tensor.expand(new_shape) + + self._is_cuda = not self._wp_array.device.is_cpu # type: ignore + self._torch_stream = self._setup_stream() + + def _setup_stream(self) -> Optional[torch.cuda.Stream]: + """Setup appropriate stream for the device.""" + if not self._is_cuda: + return None + + try: + warp_stream = wp.get_stream(self._wp_array.device) + return torch.cuda.ExternalStream(warp_stream.cuda_stream) + except Exception as e: + # Fallback to default stream if external stream creation fails. + print(f"Warning: Could not create external stream: {e}") + return torch.cuda.current_stream(self._tensor.device) + + @property + def wp_array(self) -> wp.array: + return self._wp_array + + def __repr__(self) -> str: + """Return string representation of the underlying tensor.""" + return repr(self._tensor) + + def __getitem__(self, idx: Any) -> Any: + """Get item(s) from the tensor using standard indexing.""" + return self._tensor[idx] + + def __setitem__(self, idx: Any, value: Any) -> None: + """Set item(s) in the tensor using standard indexing.""" + if self._is_cuda and self._torch_stream is not None: + with torch.cuda.stream(self._torch_stream): + self._tensor[idx] = value + else: + self._tensor[idx] = value + + def __getattr__(self, name: str) -> Any: + """Delegate attribute access to the underlying tensor.""" + return getattr(self._tensor, name) + + @classmethod + def __torch_function__( + cls, + func: Any, + types: Tuple[type, ...], + args: Tuple[Any, ...] = (), + kwargs: Optional[Dict[str, Any]] = None, + ) -> Any: + """Intercept torch.* function calls to unwrap TorchArray objects.""" + if kwargs is None: + kwargs = {} + + # Only intercept when at least one argument is our proxy. + if not any(issubclass(t, cls) for t in types): + return NotImplemented + + def _unwrap(x: Any) -> Any: + """Unwrap TorchArray objects to their underlying tensors.""" + return x._tensor if isinstance(x, cls) else x + + # Unwrap all TorchArray objects in args and kwargs. + unwrapped_args = tuple(_unwrap(arg) for arg in args) + unwrapped_kwargs = {k: _unwrap(v) for k, v in kwargs.items()} + + return func(*unwrapped_args, **unwrapped_kwargs) + + # Arithmetic operators. + + def __add__(self, other: Any) -> Any: + return self._tensor + other + + def __radd__(self, other: Any) -> Any: + return other + self._tensor + + def __sub__(self, other: Any) -> Any: + return self._tensor - other + + def __rsub__(self, other: Any) -> Any: + return other - self._tensor + + def __mul__(self, other: Any) -> Any: + return self._tensor * other + + def __rmul__(self, other: Any) -> Any: + return other * self._tensor + + def __truediv__(self, other: Any) -> Any: + return self._tensor / other + + def __rtruediv__(self, other: Any) -> Any: + return other / self._tensor + + def __pow__(self, other: Any) -> Any: + return self._tensor**other + + def __rpow__(self, other: Any) -> Any: + return other**self._tensor + + def __neg__(self) -> Any: + return -self._tensor + + def __pos__(self) -> Any: + return +self._tensor + + def __abs__(self) -> Any: + return abs(self._tensor) + + # Comparison operators. + + def __eq__(self, other: Any) -> Any: + return self._tensor == other + + def __ne__(self, other: Any) -> Any: + return self._tensor != other + + def __lt__(self, other: Any) -> Any: + return self._tensor < other + + def __le__(self, other: Any) -> Any: + return self._tensor <= other + + def __gt__(self, other: Any) -> Any: + return self._tensor > other + + def __ge__(self, other: Any) -> Any: + return self._tensor >= other + + +def _contains_warp_arrays(obj: Any) -> bool: + """Check if an object or its attributes contain any Warp arrays.""" + if isinstance(obj, wp.array): + return True + + # Check if it's a struct-like object with attributes + if hasattr(obj, "__dict__"): + return any( + isinstance(getattr(obj, attr), wp.array) + for attr in dir(obj) + if not attr.startswith("_") + ) + + return False + + +class WarpBridge(Generic[T]): + """Wraps mjwarp objects to expose Warp arrays as PyTorch tensors. + + Automatically converts Warp array attributes to TorchArray objects + on access, enabling direct PyTorch operations on simulation data. + Recursively wraps nested structures that contain Warp arrays. + + IMPORTANT: This wrapper is read-only. To modify array data, use + in-place operations like `obj.field[:] = value`. Direct assignment + like `obj.field = new_array` will raise an AttributeError to prevent + accidental memory address changes that break CUDA graphs. + """ + + def __init__(self, struct: T, nworld: int | None = None) -> None: + object.__setattr__(self, "_struct", struct) + object.__setattr__(self, "_wrapped_cache", {}) + object.__setattr__(self, "_nworld", nworld) + + def __getattr__(self, name: str) -> Any: + """Get attribute from the wrapped data, wrapping Warp arrays as TorchArray.""" + # Check cache first to avoid recreating wrappers. + if name in self._wrapped_cache: + return self._wrapped_cache[name] + + val = getattr(self._struct, name) + + # Wrap Warp arrays. + if isinstance(val, wp.array): + wrapped = TorchArray(val, nworld=self._nworld) + self._wrapped_cache[name] = wrapped + return wrapped + + # Recursively wrap nested structures that contain Warp arrays. + if _contains_warp_arrays(val): + wrapped = WarpBridge(val, nworld=self._nworld) + self._wrapped_cache[name] = wrapped + return wrapped + + return val + + def __setattr__(self, name: str, value: Any) -> None: + """Prevent attribute setting to maintain CUDA graph safety.""" + raise AttributeError( + f"Cannot set attribute '{name}' on WarpBridge. " + f"This wrapper is read-only to preserve memory addresses for CUDA graphs. " + f"Use in-place operations instead: obj.{name}[:] = value" + ) + + def __repr__(self) -> str: + """Return string representation of the wrapped struct.""" + return f"WarpBridge({repr(self._struct)})" + + @property + def struct(self) -> T: + """Access the underlying wrapped struct.""" + return self._struct + + def clear_cache(self) -> None: + """Clear the wrapped cache to force re-wrapping of arrays. + + This should be called after operations that modify the underlying warp arrays, + such as expand_model_fields(), to ensure the cache reflects the updated arrays. + """ + object.__setattr__(self, "_wrapped_cache", {}) diff --git a/mjlab/src/mjlab/tasks/__init__.py b/mjlab/src/mjlab/tasks/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..26c873b7aeaf19debe87fb231576e64859d6667b --- /dev/null +++ b/mjlab/src/mjlab/tasks/__init__.py @@ -0,0 +1,5 @@ +from mjlab.utils.lab_api.tasks.importer import import_packages + +_BLACKLIST_PKGS = ["utils", ".mdp"] + +import_packages(__name__, _BLACKLIST_PKGS) diff --git a/mjlab/src/mjlab/tasks/registry.py b/mjlab/src/mjlab/tasks/registry.py new file mode 100644 index 0000000000000000000000000000000000000000..53e1b625811c3ac2413a8e6184bbcf9766fa4dd6 --- /dev/null +++ b/mjlab/src/mjlab/tasks/registry.py @@ -0,0 +1,71 @@ +"""Task registry system for managing environment registration and creation.""" + +from copy import deepcopy +from dataclasses import dataclass + +from mjlab.envs import ManagerBasedRlEnvCfg +from mjlab.rl import RslRlOnPolicyRunnerCfg + + +@dataclass +class _TaskCfg: + env_cfg: ManagerBasedRlEnvCfg + play_env_cfg: ManagerBasedRlEnvCfg + rl_cfg: RslRlOnPolicyRunnerCfg + runner_cls: type | None + + +# Private module-level registry: task_id -> task config. +_REGISTRY: dict[str, _TaskCfg] = {} + + +def register_mjlab_task( + task_id: str, + env_cfg: ManagerBasedRlEnvCfg, + play_env_cfg: ManagerBasedRlEnvCfg, + rl_cfg: RslRlOnPolicyRunnerCfg, + runner_cls: type | None = None, +) -> None: + """Register an environment task. + + Args: + task_id: Unique task identifier (e.g., "Mjlab-Velocity-Rough-Unitree-Go1"). + env_cfg: Environment configuration used for training. + play_env_cfg: Environment configuration in "play" mode. + rl_cfg: RL runner configuration. + runner_cls: Optional custom runner class. If None, uses OnPolicyRunner. + """ + if task_id in _REGISTRY: + raise ValueError(f"Task '{task_id}' is already registered") + _REGISTRY[task_id] = _TaskCfg(env_cfg, play_env_cfg, rl_cfg, runner_cls) + + +def list_tasks() -> list[str]: + """List all registered task IDs.""" + return sorted(_REGISTRY.keys()) + + +def load_env_cfg(task_name: str, play: bool = False) -> ManagerBasedRlEnvCfg: + """Load environment configuration for a task. + + Returns a deep copy to prevent mutation of the registered config. + """ + return deepcopy( + _REGISTRY[task_name].env_cfg if not play else _REGISTRY[task_name].play_env_cfg + ) + + +def load_rl_cfg(task_name: str) -> RslRlOnPolicyRunnerCfg: + """Load RL configuration for a task. + + Returns a deep copy to prevent mutation of the registered config. + """ + return deepcopy(_REGISTRY[task_name].rl_cfg) + + +def load_runner_cls(task_name: str) -> type | None: + """Load the runner class for a task. + + If None, the default OnPolicyRunner will be used. + """ + return _REGISTRY[task_name].runner_cls diff --git a/mjlab/src/mjlab/terrains/README.md b/mjlab/src/mjlab/terrains/README.md new file mode 100644 index 0000000000000000000000000000000000000000..bd7c8289be59559863d1eddb7b9a983a4dd45381 --- /dev/null +++ b/mjlab/src/mjlab/terrains/README.md @@ -0,0 +1,5 @@ +# Terrains + +Procedurally generate terrains using primitive geometries and heightfields. + +Rough Terrain diff --git a/mjlab/src/mjlab/terrains/__init__.py b/mjlab/src/mjlab/terrains/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..9a7533e2a9ac1f23e018b33d9c287f8a97514ce6 --- /dev/null +++ b/mjlab/src/mjlab/terrains/__init__.py @@ -0,0 +1,52 @@ +from mjlab.terrains.heightfield_terrains import ( + HfDiscreteObstaclesTerrainCfg as HfDiscreteObstaclesTerrainCfg, +) +from mjlab.terrains.heightfield_terrains import ( + HfPerlinNoiseTerrainCfg as HfPerlinNoiseTerrainCfg, +) +from mjlab.terrains.heightfield_terrains import ( + HfPyramidSlopedTerrainCfg as HfPyramidSlopedTerrainCfg, +) +from mjlab.terrains.heightfield_terrains import ( + HfRandomUniformTerrainCfg as HfRandomUniformTerrainCfg, +) +from mjlab.terrains.heightfield_terrains import HfWaveTerrainCfg as HfWaveTerrainCfg +from mjlab.terrains.primitive_terrains import BoxFlatTerrainCfg as BoxFlatTerrainCfg +from mjlab.terrains.primitive_terrains import ( + BoxInvertedPyramidStairsTerrainCfg as BoxInvertedPyramidStairsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxNarrowBeamsTerrainCfg as BoxNarrowBeamsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxNestedRingsTerrainCfg as BoxNestedRingsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxOpenStairsTerrainCfg as BoxOpenStairsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxPyramidStairsTerrainCfg as BoxPyramidStairsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxRandomGridTerrainCfg as BoxRandomGridTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxRandomSpreadTerrainCfg as BoxRandomSpreadTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxRandomStairsTerrainCfg as BoxRandomStairsTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxSteppingStonesTerrainCfg as BoxSteppingStonesTerrainCfg, +) +from mjlab.terrains.primitive_terrains import ( + BoxTiltedGridTerrainCfg as BoxTiltedGridTerrainCfg, +) +from mjlab.terrains.terrain_generator import ( + FlatPatchSamplingCfg as FlatPatchSamplingCfg, +) +from mjlab.terrains.terrain_generator import SubTerrainCfg as SubTerrainCfg +from mjlab.terrains.terrain_generator import TerrainGenerator as TerrainGenerator +from mjlab.terrains.terrain_generator import TerrainGeneratorCfg as TerrainGeneratorCfg +from mjlab.terrains.terrain_importer import TerrainImporter as TerrainImporter +from mjlab.terrains.terrain_importer import TerrainImporterCfg as TerrainImporterCfg diff --git a/mjlab/src/mjlab/terrains/config.py b/mjlab/src/mjlab/terrains/config.py new file mode 100644 index 0000000000000000000000000000000000000000..6dbd6dd28739c1ac42e580f77bf843fe553f3f33 --- /dev/null +++ b/mjlab/src/mjlab/terrains/config.py @@ -0,0 +1,199 @@ +import mujoco + +import mjlab.terrains as terrain_gen +from mjlab.terrains.terrain_generator import TerrainGeneratorCfg +from mjlab.terrains.terrain_importer import TerrainImporter, TerrainImporterCfg + +ROUGH_TERRAINS_CFG = TerrainGeneratorCfg( + size=(8.0, 8.0), + border_width=20.0, + num_rows=10, + num_cols=20, + sub_terrains={ + "flat": terrain_gen.BoxFlatTerrainCfg(proportion=0.2), + "pyramid_stairs": terrain_gen.BoxPyramidStairsTerrainCfg( + proportion=0.2, + step_height_range=(0.0, 0.1), + step_width=0.3, + platform_width=3.0, + border_width=1.0, + ), + "pyramid_stairs_inv": terrain_gen.BoxInvertedPyramidStairsTerrainCfg( + proportion=0.2, + step_height_range=(0.0, 0.1), + step_width=0.3, + platform_width=3.0, + border_width=1.0, + ), + "hf_pyramid_slope": terrain_gen.HfPyramidSlopedTerrainCfg( + proportion=0.1, + slope_range=(0.0, 1.0), + platform_width=2.0, + border_width=0.25, + ), + "hf_pyramid_slope_inv": terrain_gen.HfPyramidSlopedTerrainCfg( + proportion=0.1, + slope_range=(0.0, 1.0), + platform_width=2.0, + border_width=0.25, + inverted=True, + ), + "random_rough": terrain_gen.HfRandomUniformTerrainCfg( + proportion=0.1, + noise_range=(0.02, 0.10), + noise_step=0.02, + border_width=0.25, + ), + "wave_terrain": terrain_gen.HfWaveTerrainCfg( + proportion=0.1, + amplitude_range=(0.0, 0.2), + num_waves=4, + border_width=0.25, + ), + }, + add_lights=True, +) + +ALL_TERRAINS_CFG = TerrainGeneratorCfg( + size=(8.0, 8.0), + border_width=20.0, + num_rows=10, + num_cols=16, + sub_terrains={ + "flat": terrain_gen.BoxFlatTerrainCfg(proportion=1.0), + "pyramid_stairs": terrain_gen.BoxPyramidStairsTerrainCfg( + proportion=1.0, + step_height_range=(0.0, 0.2), + step_width=0.3, + platform_width=3.0, + border_width=1.0, + ), + "pyramid_stairs_inv": terrain_gen.BoxInvertedPyramidStairsTerrainCfg( + proportion=1.0, + step_height_range=(0.0, 0.2), + step_width=0.3, + platform_width=3.0, + border_width=1.0, + ), + "hf_pyramid_slope": terrain_gen.HfPyramidSlopedTerrainCfg( + proportion=1.0, + slope_range=(0.0, 0.7), + platform_width=2.0, + border_width=0.25, + ), + "random_rough": terrain_gen.HfRandomUniformTerrainCfg( + proportion=1.0, + noise_range=(0.02, 0.10), + noise_step=0.02, + border_width=0.25, + ), + "wave_terrain": terrain_gen.HfWaveTerrainCfg( + proportion=1.0, + amplitude_range=(0.0, 0.2), + num_waves=4, + border_width=0.25, + ), + "discrete_obstacles": terrain_gen.HfDiscreteObstaclesTerrainCfg( + proportion=1.0, + obstacle_width_range=(0.3, 1.0), + obstacle_height_range=(0.05, 0.3), + num_obstacles=40, + border_width=0.25, + ), + "perlin_noise": terrain_gen.HfPerlinNoiseTerrainCfg( + proportion=1.0, + height_range=(0.0, 1.0), + octaves=4, + persistence=0.3, + lacunarity=2.0, + scale=10.0, + horizontal_scale=0.1, + border_width=0.50, + ), + "box_random_grid": terrain_gen.BoxRandomGridTerrainCfg( + proportion=1.0, + grid_width=0.4, + grid_height_range=(0.0, 0.3), + platform_width=1.0, + ), + "random_spread_boxes": terrain_gen.BoxRandomSpreadTerrainCfg( + proportion=1.0, + num_boxes=80, + box_width_range=(0.1, 1.0), + box_length_range=(0.1, 2.0), + box_height_range=(0.05, 0.3), + platform_width=1.0, + border_width=0.25, + ), + "open_stairs": terrain_gen.BoxOpenStairsTerrainCfg( + proportion=1.0, + step_height_range=(0.1, 0.2), + step_width_range=(0.4, 0.8), + platform_width=1.0, + border_width=0.25, + ), + "random_stairs": terrain_gen.BoxRandomStairsTerrainCfg( + proportion=1.0, + step_width=0.8, + step_height_range=(0.1, 0.3), + platform_width=1.0, + border_width=0.25, + ), + "stepping_stones": terrain_gen.BoxSteppingStonesTerrainCfg( + proportion=1.0, + stone_size_range=(0.4, 0.8), + stone_distance_range=(0.2, 0.5), + stone_height=0.2, + stone_height_variation=0.1, + stone_size_variation=0.2, + displacement_range=0.1, + floor_depth=2.0, + platform_width=1.0, + border_width=0.25, + ), + "narrow_beams": terrain_gen.BoxNarrowBeamsTerrainCfg( + proportion=1.0, + num_beams=12, + beam_width_range=(0.2, 0.8), + beam_height=0.2, + spacing=0.8, + platform_width=1.0, + border_width=0.25, + floor_depth=2.0, + ), + "nested_rings": terrain_gen.BoxNestedRingsTerrainCfg( + proportion=1.0, + num_rings=8, + ring_width_range=(0.3, 0.6), + gap_range=(0.1, 0.4), + height_range=(0.1, 0.4), + platform_width=1.0, + border_width=0.25, + floor_depth=2.0, + ), + "tilted_grid": terrain_gen.BoxTiltedGridTerrainCfg( + proportion=1.0, + grid_width=1.0, + tilt_range_deg=20.0, + height_range=0.3, + platform_width=1.0, + border_width=0.25, + floor_depth=2.0, + ), + }, + add_lights=True, +) + + +if __name__ == "__main__": + import mujoco.viewer + import torch + + device = "cuda" if torch.cuda.is_available() else "cpu" + + terrain_cfg = TerrainImporterCfg( + terrain_type="generator", + terrain_generator=ROUGH_TERRAINS_CFG, + ) + terrain = TerrainImporter(terrain_cfg, device=device) + mujoco.viewer.launch(terrain.spec.compile()) diff --git a/mjlab/src/mjlab/terrains/heightfield_terrains.py b/mjlab/src/mjlab/terrains/heightfield_terrains.py new file mode 100644 index 0000000000000000000000000000000000000000..0e4ce8f25b4d4638d2f7236dce1132a16034cf90 --- /dev/null +++ b/mjlab/src/mjlab/terrains/heightfield_terrains.py @@ -0,0 +1,936 @@ +"""Terrains composed of heightfields. + +This module provides terrain generation functionality using heightfields, +adapted from the IsaacLab terrain generation system. + +References: + IsaacLab mesh terrain implementation: + https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab/isaaclab/terrains/height_field/hf_terrains.py +""" + +import uuid +from dataclasses import dataclass +from typing import Literal + +import mujoco +import numpy as np +import scipy.interpolate as interpolate +from scipy import ndimage + +from mjlab.terrains.terrain_generator import ( + SubTerrainCfg, + TerrainGeometry, + TerrainOutput, +) +from mjlab.terrains.utils import find_flat_patches_from_heightfield + + +def color_by_height( + spec: mujoco.MjSpec, + noise: np.ndarray, + unique_id: str, + normalized_elevation: np.ndarray, + texture_size: int = 128, +) -> str: + texture_name = f"hf_texture_{unique_id}" + texture = spec.add_texture( + name=texture_name, + type=mujoco.mjtTexture.mjTEXTURE_2D, + width=texture_size, + height=texture_size, + ) + + texture_elevation = ndimage.zoom( + normalized_elevation, + (texture_size / noise.shape[0], texture_size / noise.shape[1]), + order=1, + ) + texture_elevation = np.asarray(texture_elevation) + + hue = 0.5 - texture_elevation * 0.45 + saturation = 0.6 - texture_elevation * 0.2 + value = 0.4 + texture_elevation * 0.3 + + c = value * saturation + x = c * (1 - np.abs((hue * 6) % 2 - 1)) + m = value - c + + hue_sector = (hue * 6).astype(int) % 6 + + r = np.zeros_like(hue) + g = np.zeros_like(hue) + b = np.zeros_like(hue) + + mask = hue_sector == 0 + r[mask] = c[mask] + g[mask] = x[mask] + + mask = hue_sector == 1 + r[mask] = x[mask] + g[mask] = c[mask] + + mask = hue_sector == 2 + g[mask] = c[mask] + b[mask] = x[mask] + + mask = hue_sector == 3 + g[mask] = x[mask] + b[mask] = c[mask] + + mask = hue_sector == 4 + r[mask] = x[mask] + b[mask] = c[mask] + + mask = hue_sector == 5 + r[mask] = c[mask] + b[mask] = x[mask] + + r += m + g += m + b += m + + rgb_data = np.stack([r, g, b], axis=-1) + rgb_data = (rgb_data * 255).astype(np.uint8) + + rgb_data = np.flipud(rgb_data) + texture.data = rgb_data.tobytes() + + material_name = f"hf_material_{unique_id}" + material = spec.add_material(name=material_name) + material.textures[mujoco.mjtTextureRole.mjTEXROLE_RGB] = texture_name + + return material_name + + +def _fractal_perlin_noise_2d( + x_size: int, + y_size: int, + rng: np.random.Generator, + octaves: int = 4, + persistence: float = 0.5, + lacunarity: float = 2.0, + scale: float = 1.0, +) -> np.ndarray: + """Generate 2D fractal Perlin noise.""" + + def lerp(a, b, x): + return a + x * (b - a) + + def fade(t): + return t * t * t * (t * (t * 6 - 15) + 10) + + def gradient(h, x, y): + h = h % 4 + return np.where( + h == 0, + x + y, + np.where(h == 1, x - y, np.where(h == 2, -x + y, -x - y)), + ) + + def perlin(x, y, p): + xi = x.astype(int) % 256 + yi = y.astype(int) % 256 + xf = x - x.astype(int) + yf = y - y.astype(int) + u = fade(xf) + v = fade(yf) + + n00 = gradient(p[p[xi] + yi], xf, yf) + n01 = gradient(p[p[xi] + yi + 1], xf, yf - 1) + n11 = gradient(p[p[xi + 1] + yi + 1], xf - 1, yf - 1) + n10 = gradient(p[p[xi + 1] + yi], xf - 1, yf) + + x1 = lerp(n00, n10, u) + x2 = lerp(n01, n11, u) + return lerp(x1, x2, v) + + p = np.arange(256, dtype=int) + rng.shuffle(p) + p = np.stack([p, p]).flatten() + + noise = np.zeros((x_size, y_size)) + amplitude = 1.0 + frequency = scale + total_amplitude = 0.0 + + x = np.linspace(0, x_size, x_size, endpoint=False) + y = np.linspace(0, y_size, y_size, endpoint=False) + xx, yy = np.meshgrid(x, y, indexing="ij") + + for _ in range(octaves): + noise += amplitude * perlin(xx * frequency / x_size, yy * frequency / y_size, p) + total_amplitude += amplitude + amplitude *= persistence + frequency *= lacunarity + + return noise / total_amplitude + + +def _compute_flat_patches( + noise: np.ndarray, + vertical_scale: float, + horizontal_scale: float, + z_offset: float, + flat_patch_sampling: dict | None, + rng: np.random.Generator, +) -> dict[str, np.ndarray] | None: + """Compute flat patches for a heightfield terrain if configured.""" + if flat_patch_sampling is None: + return None + physical_heights = (noise.astype(np.float64) - noise.min()) * vertical_scale + flat_patches: dict[str, np.ndarray] = {} + for name, patch_cfg in flat_patch_sampling.items(): + flat_patches[name] = find_flat_patches_from_heightfield( + heights=physical_heights, + horizontal_scale=horizontal_scale, + z_offset=z_offset, + cfg=patch_cfg, + rng=rng, + ) + return flat_patches + + +@dataclass(kw_only=True) +class HfPyramidSlopedTerrainCfg(SubTerrainCfg): + slope_range: tuple[float, float] + """Range of slope gradients (rise / run), interpolated by difficulty.""" + platform_width: float = 1.0 + """Side length of the flat square platform at the terrain center, in meters.""" + inverted: bool = False + """If True, the pyramid is inverted so the platform is at the bottom.""" + border_width: float = 0.0 + """Width of the flat border around the terrain edges, in meters. Must be >= + horizontal_scale if non-zero.""" + horizontal_scale: float = 0.1 + """Heightfield grid resolution along x and y, in meters per cell.""" + vertical_scale: float = 0.005 + """Heightfield height resolution, in meters per integer unit of the noise array.""" + base_thickness_ratio: float = 1.0 + """Ratio of the heightfield base thickness to its maximum surface height.""" + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + + if self.inverted: + slope = -self.slope_range[0] - difficulty * ( + self.slope_range[1] - self.slope_range[0] + ) + else: + slope = self.slope_range[0] + difficulty * ( + self.slope_range[1] - self.slope_range[0] + ) + + if self.border_width > 0 and self.border_width < self.horizontal_scale: + raise ValueError( + f"Border width ({self.border_width}) must be >= horizontal scale " + f"({self.horizontal_scale})" + ) + + border_pixels = int(self.border_width / self.horizontal_scale) + width_pixels = int(self.size[0] / self.horizontal_scale) + length_pixels = int(self.size[1] / self.horizontal_scale) + + inner_width_pixels = width_pixels - 2 * border_pixels + inner_length_pixels = length_pixels - 2 * border_pixels + + noise = np.zeros((width_pixels, length_pixels), dtype=np.int16) + + if border_pixels > 0: + height_max = int( + slope * (inner_width_pixels * self.horizontal_scale) / 2 / self.vertical_scale + ) + + center_x = int(inner_width_pixels / 2) + center_y = int(inner_length_pixels / 2) + + x = np.arange(0, inner_width_pixels) + y = np.arange(0, inner_length_pixels) + xx, yy = np.meshgrid(x, y, sparse=True) + + xx = (center_x - np.abs(center_x - xx)) / center_x + yy = (center_y - np.abs(center_y - yy)) / center_y + + xx = xx.reshape(inner_width_pixels, 1) + yy = yy.reshape(1, inner_length_pixels) + + hf_raw = height_max * xx * yy + + platform_width = int(self.platform_width / self.horizontal_scale / 2) + x_pf = inner_width_pixels // 2 - platform_width + y_pf = inner_length_pixels // 2 - platform_width + z_pf = hf_raw[x_pf, y_pf] if x_pf >= 0 and y_pf >= 0 else 0 + hf_raw = np.clip(hf_raw, min(0, z_pf), max(0, z_pf)) + + noise[ + border_pixels : -border_pixels if border_pixels else width_pixels, + border_pixels : -border_pixels if border_pixels else length_pixels, + ] = np.rint(hf_raw).astype(np.int16) + else: + height_max = int(slope * self.size[0] / 2 / self.vertical_scale) + + center_x = int(width_pixels / 2) + center_y = int(length_pixels / 2) + + x = np.arange(0, width_pixels) + y = np.arange(0, length_pixels) + xx, yy = np.meshgrid(x, y, sparse=True) + + xx = (center_x - np.abs(center_x - xx)) / center_x + yy = (center_y - np.abs(center_y - yy)) / center_y + + xx = xx.reshape(width_pixels, 1) + yy = yy.reshape(1, length_pixels) + + hf_raw = height_max * xx * yy + + platform_width = int(self.platform_width / self.horizontal_scale / 2) + x_pf = width_pixels // 2 - platform_width + y_pf = length_pixels // 2 - platform_width + z_pf = hf_raw[x_pf, y_pf] + hf_raw = np.clip(hf_raw, min(0, z_pf), max(0, z_pf)) + + noise = np.rint(hf_raw).astype(np.int16) + + elevation_min = np.min(noise) + elevation_max = np.max(noise) + elevation_range = ( + elevation_max - elevation_min if elevation_max != elevation_min else 1 + ) + + max_physical_height = elevation_range * self.vertical_scale + base_thickness = max_physical_height * self.base_thickness_ratio + + if elevation_range > 0: + normalized_elevation = (noise - elevation_min) / elevation_range + else: + normalized_elevation = np.zeros_like(noise) + + unique_id = uuid.uuid4().hex + field = spec.add_hfield( + name=f"hfield_{unique_id}", + size=[ + self.size[0] / 2, + self.size[1] / 2, + max_physical_height, + base_thickness, + ], + nrow=noise.shape[0], + ncol=noise.shape[1], + userdata=normalized_elevation.flatten().astype(np.float32).tolist(), + ) + + if self.inverted: + hfield_z_offset = -max_physical_height + else: + hfield_z_offset = 0 + + material_name = color_by_height(spec, noise, unique_id, normalized_elevation) + + hfield_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_HFIELD, + hfieldname=field.name, + pos=[ + self.size[0] / 2, + self.size[1] / 2, + hfield_z_offset, + ], + material=material_name, + ) + + if self.inverted: + spawn_height = hfield_z_offset + else: + spawn_height = max_physical_height + + origin = np.array([self.size[0] / 2, self.size[1] / 2, spawn_height]) + + flat_patches = _compute_flat_patches( + noise, + self.vertical_scale, + self.horizontal_scale, + hfield_z_offset, + self.flat_patch_sampling, + rng, + ) + + geom = TerrainGeometry(geom=hfield_geom, hfield=field) + return TerrainOutput(origin=origin, geometries=[geom], flat_patches=flat_patches) + + +@dataclass(kw_only=True) +class HfRandomUniformTerrainCfg(SubTerrainCfg): + noise_range: tuple[float, float] + """Min and max height noise, in meters.""" + noise_step: float = 0.005 + """Height quantization step, in meters. Sampled heights are multiples of this + value within noise_range.""" + downsampled_scale: float | None = None + """Spacing between randomly sampled height points before interpolation, in + meters. If None, uses horizontal_scale. Must be >= horizontal_scale.""" + horizontal_scale: float = 0.1 + """Heightfield grid resolution along x and y, in meters per cell.""" + vertical_scale: float = 0.005 + """Heightfield height resolution, in meters per integer unit of the noise array.""" + base_thickness_ratio: float = 1.0 + """Ratio of the heightfield base thickness to its maximum surface height.""" + border_width: float = 0.0 + """Width of the flat border around the terrain edges, in meters. Must be >= + horizontal_scale if non-zero.""" + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + del difficulty # Unused. + + body = spec.body("terrain") + + if self.border_width > 0 and self.border_width < self.horizontal_scale: + raise ValueError( + f"Border width ({self.border_width}) must be >= horizontal scale " + f"({self.horizontal_scale})" + ) + + if self.downsampled_scale is None: + downsampled_scale = self.horizontal_scale + elif self.downsampled_scale < self.horizontal_scale: + raise ValueError( + f"Downsampled scale must be >= horizontal scale: " + f"{self.downsampled_scale} < {self.horizontal_scale}" + ) + else: + downsampled_scale = self.downsampled_scale + + border_pixels = int(self.border_width / self.horizontal_scale) + width_pixels = int(self.size[0] / self.horizontal_scale) + length_pixels = int(self.size[1] / self.horizontal_scale) + + noise = np.zeros((width_pixels, length_pixels), dtype=np.int16) + + if border_pixels > 0: + inner_width_pixels = width_pixels - 2 * border_pixels + inner_length_pixels = length_pixels - 2 * border_pixels + inner_size = ( + inner_width_pixels * self.horizontal_scale, + inner_length_pixels * self.horizontal_scale, + ) + + width_downsampled = int(inner_size[0] / downsampled_scale) + length_downsampled = int(inner_size[1] / downsampled_scale) + + height_min = int(self.noise_range[0] / self.vertical_scale) + height_max = int(self.noise_range[1] / self.vertical_scale) + height_step = int(self.noise_step / self.vertical_scale) + + height_range = np.arange(height_min, height_max + height_step, height_step) + height_field_downsampled = rng.choice( + height_range, size=(width_downsampled, length_downsampled) + ) + + x = np.linspace(0, inner_size[0], width_downsampled) + y = np.linspace(0, inner_size[1], length_downsampled) + func = interpolate.RectBivariateSpline(x, y, height_field_downsampled) + + x_upsampled = np.linspace(0, inner_size[0], inner_width_pixels) + y_upsampled = np.linspace(0, inner_size[1], inner_length_pixels) + z_upsampled = func(x_upsampled, y_upsampled) + + noise[ + border_pixels : -border_pixels if border_pixels else width_pixels, + border_pixels : -border_pixels if border_pixels else length_pixels, + ] = np.rint(z_upsampled).astype(np.int16) + else: + width_downsampled = int(self.size[0] / downsampled_scale) + length_downsampled = int(self.size[1] / downsampled_scale) + height_min = int(self.noise_range[0] / self.vertical_scale) + height_max = int(self.noise_range[1] / self.vertical_scale) + height_step = int(self.noise_step / self.vertical_scale) + + height_range = np.arange(height_min, height_max + height_step, height_step) + height_field_downsampled = rng.choice( + height_range, size=(width_downsampled, length_downsampled) + ) + + x = np.linspace(0, self.size[0], width_downsampled) + y = np.linspace(0, self.size[1], length_downsampled) + func = interpolate.RectBivariateSpline(x, y, height_field_downsampled) + + x_upsampled = np.linspace(0, self.size[0], width_pixels) + y_upsampled = np.linspace(0, self.size[1], length_pixels) + z_upsampled = func(x_upsampled, y_upsampled) + noise = np.rint(z_upsampled).astype(np.int16) + + elevation_min = np.min(noise) + elevation_max = np.max(noise) + elevation_range = ( + elevation_max - elevation_min if elevation_max != elevation_min else 1 + ) + + max_physical_height = elevation_range * self.vertical_scale + base_thickness = max_physical_height * self.base_thickness_ratio + + if elevation_range > 0: + normalized_elevation = (noise - elevation_min) / elevation_range + else: + normalized_elevation = np.zeros_like(noise) + + unique_id = uuid.uuid4().hex + field = spec.add_hfield( + name=f"hfield_{unique_id}", + size=[ + self.size[0] / 2, + self.size[1] / 2, + max_physical_height, + base_thickness, + ], + nrow=noise.shape[0], + ncol=noise.shape[1], + userdata=normalized_elevation.flatten().astype(np.float32).tolist(), + ) + + material_name = color_by_height(spec, noise, unique_id, normalized_elevation) + + hfield_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_HFIELD, + hfieldname=field.name, + pos=[self.size[0] / 2, self.size[1] / 2, 0], + material=material_name, + ) + + spawn_height = (self.noise_range[0] + self.noise_range[1]) / 2 + origin = np.array([self.size[0] / 2, self.size[1] / 2, spawn_height]) + + flat_patches = _compute_flat_patches( + noise, + self.vertical_scale, + self.horizontal_scale, + 0, + self.flat_patch_sampling, + rng, + ) + + geom = TerrainGeometry(geom=hfield_geom, hfield=field) + return TerrainOutput(origin=origin, geometries=[geom], flat_patches=flat_patches) + + +@dataclass(kw_only=True) +class HfWaveTerrainCfg(SubTerrainCfg): + amplitude_range: tuple[float, float] + """Min and max wave amplitude, in meters. Interpolated by difficulty.""" + num_waves: int = 1 + """Number of complete wave cycles along the terrain length.""" + horizontal_scale: float = 0.1 + """Heightfield grid resolution along x and y, in meters per cell.""" + vertical_scale: float = 0.005 + """Heightfield height resolution, in meters per integer unit of the noise array.""" + base_thickness_ratio: float = 0.25 + """Ratio of the heightfield base thickness to its maximum surface height.""" + border_width: float = 0.0 + """Width of the flat border around the terrain edges, in meters. Must be >= + horizontal_scale if non-zero.""" + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + + if self.num_waves <= 0: + raise ValueError(f"Number of waves must be positive. Got: {self.num_waves}") + + if self.border_width > 0 and self.border_width < self.horizontal_scale: + raise ValueError( + f"Border width ({self.border_width}) must be >= horizontal scale " + f"({self.horizontal_scale})" + ) + + amplitude = self.amplitude_range[0] + difficulty * ( + self.amplitude_range[1] - self.amplitude_range[0] + ) + + border_pixels = int(self.border_width / self.horizontal_scale) + width_pixels = int(self.size[0] / self.horizontal_scale) + length_pixels = int(self.size[1] / self.horizontal_scale) + + noise = np.zeros((width_pixels, length_pixels), dtype=np.int16) + + if border_pixels > 0: + inner_width_pixels = width_pixels - 2 * border_pixels + inner_length_pixels = length_pixels - 2 * border_pixels + + amplitude_pixels = int(0.5 * amplitude / self.vertical_scale) + wave_length = inner_length_pixels / self.num_waves + wave_number = 2 * np.pi / wave_length + + x = np.arange(0, inner_width_pixels) + y = np.arange(0, inner_length_pixels) + xx, yy = np.meshgrid(x, y, sparse=True) + xx = xx.reshape(inner_width_pixels, 1) + yy = yy.reshape(1, inner_length_pixels) + + hf_raw = amplitude_pixels * (np.cos(yy * wave_number) + np.sin(xx * wave_number)) + + noise[ + border_pixels : -border_pixels if border_pixels else width_pixels, + border_pixels : -border_pixels if border_pixels else length_pixels, + ] = np.rint(hf_raw).astype(np.int16) + else: + amplitude_pixels = int(0.5 * amplitude / self.vertical_scale) + wave_length = length_pixels / self.num_waves + wave_number = 2 * np.pi / wave_length + + x = np.arange(0, width_pixels) + y = np.arange(0, length_pixels) + xx, yy = np.meshgrid(x, y, sparse=True) + xx = xx.reshape(width_pixels, 1) + yy = yy.reshape(1, length_pixels) + + hf_raw = amplitude_pixels * (np.cos(yy * wave_number) + np.sin(xx * wave_number)) + noise = np.rint(hf_raw).astype(np.int16) + + elevation_min = np.min(noise) + elevation_max = np.max(noise) + elevation_range = ( + elevation_max - elevation_min if elevation_max != elevation_min else 1 + ) + + max_physical_height = elevation_range * self.vertical_scale + base_thickness = max_physical_height * self.base_thickness_ratio + + if elevation_range > 0: + normalized_elevation = (noise - elevation_min) / elevation_range + else: + normalized_elevation = np.zeros_like(noise) + + unique_id = uuid.uuid4().hex + field = spec.add_hfield( + name=f"hfield_{unique_id}", + size=[ + self.size[0] / 2, + self.size[1] / 2, + max_physical_height, + base_thickness, + ], + nrow=noise.shape[0], + ncol=noise.shape[1], + userdata=normalized_elevation.flatten().astype(np.float32).tolist(), + ) + + material_name = color_by_height(spec, noise, unique_id, normalized_elevation) + + hfield_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_HFIELD, + hfieldname=field.name, + pos=[self.size[0] / 2, self.size[1] / 2, -max_physical_height / 2], + material=material_name, + ) + + spawn_height = 0.0 + origin = np.array([self.size[0] / 2, self.size[1] / 2, spawn_height]) + + flat_patches = _compute_flat_patches( + noise, + self.vertical_scale, + self.horizontal_scale, + -max_physical_height / 2, + self.flat_patch_sampling, + rng, + ) + + geom = TerrainGeometry(geom=hfield_geom, hfield=field) + return TerrainOutput(origin=origin, geometries=[geom], flat_patches=flat_patches) + + +@dataclass(kw_only=True) +class HfDiscreteObstaclesTerrainCfg(SubTerrainCfg): + obstacle_height_mode: Literal["choice", "fixed"] = "choice" + """How obstacle heights are chosen. "choice" randomly picks from [-h, -h/2, + h/2, h] (mix of pits and bumps); "fixed" uses h for all obstacles.""" + obstacle_width_range: tuple[float, float] + """Min and max obstacle width, in meters.""" + obstacle_height_range: tuple[float, float] + """Min and max obstacle height, in meters. Interpolated by difficulty.""" + num_obstacles: int + """Number of obstacles to place on the terrain.""" + platform_width: float = 1.0 + """Side length of the obstacle-free flat square at the terrain center, in meters.""" + horizontal_scale: float = 0.1 + """Heightfield grid resolution along x and y, in meters per cell.""" + vertical_scale: float = 0.005 + """Heightfield height resolution, in meters per integer unit of the noise array.""" + base_thickness_ratio: float = 1.0 + """Ratio of the heightfield base thickness to its maximum surface height.""" + border_width: float = 0.0 + """Width of the flat border around the terrain edges, in meters. Must be >= + horizontal_scale if non-zero.""" + square_obstacles: bool = False + """If True, obstacles have equal width and length. If False, each dimension + is sampled independently.""" + origin_z_offset: float = 0.0 + """Vertical offset added to spawn origin height (meters). + + Useful to prevent robot feet from clipping through terrain when spawning at + the origin. + """ + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + + if self.border_width > 0 and self.border_width < self.horizontal_scale: + raise ValueError( + f"Border width ({self.border_width}) must be >= horizontal scale " + f"({self.horizontal_scale})" + ) + + obs_height = self.obstacle_height_range[0] + difficulty * ( + self.obstacle_height_range[1] - self.obstacle_height_range[0] + ) + + border_pixels = int(self.border_width / self.horizontal_scale) + width_pixels = int(self.size[0] / self.horizontal_scale) + length_pixels = int(self.size[1] / self.horizontal_scale) + + obs_h = int(obs_height / self.vertical_scale) + obs_width_min = int(self.obstacle_width_range[0] / self.horizontal_scale) + obs_width_max = int(self.obstacle_width_range[1] / self.horizontal_scale) + platform_pixels = int(self.platform_width / self.horizontal_scale) + + if border_pixels > 0: + inner_width_pixels = width_pixels - 2 * border_pixels + inner_length_pixels = length_pixels - 2 * border_pixels + else: + inner_width_pixels = width_pixels + inner_length_pixels = length_pixels + + noise = np.zeros((inner_width_pixels, inner_length_pixels), dtype=np.int16) + + obs_width_range = np.arange(obs_width_min, obs_width_max + 1, 4) + if len(obs_width_range) == 0: + obs_width_range = np.array([obs_width_min]) + + for _ in range(self.num_obstacles): + if self.obstacle_height_mode == "choice": + h = rng.choice(np.array([-obs_h, -obs_h // 2, obs_h // 2, obs_h])) + else: + h = obs_h + + w = rng.choice(obs_width_range) + obs_len = w if self.square_obstacles else rng.choice(obs_width_range) + + x_range = np.arange(0, inner_width_pixels, 4) + y_range = np.arange(0, inner_length_pixels, 4) + if len(x_range) == 0 or len(y_range) == 0: + continue + x = rng.choice(x_range) + y = rng.choice(y_range) + + x_end = min(x + w, inner_width_pixels) + y_end = min(y + obs_len, inner_length_pixels) + noise[x:x_end, y:y_end] = h + + # Clear center platform. + cx = inner_width_pixels // 2 + cy = inner_length_pixels // 2 + half_pf = platform_pixels // 2 + x0 = max(cx - half_pf, 0) + x1 = min(cx + half_pf, inner_width_pixels) + y0 = max(cy - half_pf, 0) + y1 = min(cy + half_pf, inner_length_pixels) + noise[x0:x1, y0:y1] = 0 + + if border_pixels > 0: + outer_noise = np.zeros((width_pixels, length_pixels), dtype=np.int16) + outer_noise[ + border_pixels : border_pixels + inner_width_pixels, + border_pixels : border_pixels + inner_length_pixels, + ] = noise + noise = outer_noise + + elevation_min = np.min(noise) + elevation_max = np.max(noise) + elevation_range = ( + elevation_max - elevation_min if elevation_max != elevation_min else 1 + ) + + max_physical_height = elevation_range * self.vertical_scale + base_thickness = max_physical_height * self.base_thickness_ratio + + if elevation_range > 0: + normalized_elevation = (noise - elevation_min) / elevation_range + else: + normalized_elevation = np.zeros_like(noise) + + unique_id = uuid.uuid4().hex + field = spec.add_hfield( + name=f"hfield_{unique_id}", + size=[ + self.size[0] / 2, + self.size[1] / 2, + max_physical_height, + base_thickness, + ], + nrow=noise.shape[0], + ncol=noise.shape[1], + userdata=normalized_elevation.flatten().astype(np.float32).tolist(), + ) + + # For "choice" mode, obstacles can be negative (pits), so offset the + # geom down so that the zero-level of the noise aligns with z=0. + if self.obstacle_height_mode == "choice": + hfield_z_offset = elevation_min * self.vertical_scale + else: + hfield_z_offset = 0 + + material_name = color_by_height(spec, noise, unique_id, normalized_elevation) + + hfield_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_HFIELD, + hfieldname=field.name, + pos=[ + self.size[0] / 2, + self.size[1] / 2, + hfield_z_offset, + ], + material=material_name, + ) + + # The cleared platform (noise=0) is at z=0 due to the offset logic. + spawn_height = self.origin_z_offset + origin = np.array([self.size[0] / 2, self.size[1] / 2, spawn_height]) + + flat_patches = _compute_flat_patches( + noise, + self.vertical_scale, + self.horizontal_scale, + hfield_z_offset, + self.flat_patch_sampling, + rng, + ) + + geom = TerrainGeometry(geom=hfield_geom, hfield=field) + return TerrainOutput(origin=origin, geometries=[geom], flat_patches=flat_patches) + + +@dataclass(kw_only=True) +class HfPerlinNoiseTerrainCfg(SubTerrainCfg): + height_range: tuple[float, float] + octaves: int = 4 + persistence: float = 0.5 + lacunarity: float = 2.0 + scale: float = 10.0 + horizontal_scale: float = 0.1 + resolution: float = 0.05 + base_thickness_ratio: float = 1.0 + border_width: float = 0.0 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + + if self.border_width > 0 and self.border_width < self.horizontal_scale: + raise ValueError( + f"Border width ({self.border_width}) must be >= " + f"horizontal_scale ({self.horizontal_scale})" + ) + + target_height = self.height_range[0] + difficulty * ( + self.height_range[1] - self.height_range[0] + ) + + # Resolution is the pixel size (distance between grid points). + grid_spacing = self.resolution + + # Feature scale is affected by both 'scale' and 'horizontal_scale'. + # A larger horizontal_scale means larger features (stretched out). + effective_scale = self.scale * (self.resolution / self.horizontal_scale) + + border_pixels = int(self.border_width / grid_spacing) + width_pixels = int(self.size[0] / grid_spacing) + length_pixels = int(self.size[1] / grid_spacing) + + if border_pixels > 0: + inner_width_pixels = width_pixels - 2 * border_pixels + inner_length_pixels = length_pixels - 2 * border_pixels + noise_raw = _fractal_perlin_noise_2d( + inner_width_pixels, + inner_length_pixels, + rng, + octaves=self.octaves, + persistence=self.persistence, + lacunarity=self.lacunarity, + scale=effective_scale, + ) + # Normalize to [0, 1] + noise_min, noise_max = noise_raw.min(), noise_raw.max() + noise_range = noise_max - noise_min if noise_max > noise_min else 1.0 + inner_normalized = (noise_raw - noise_min) / noise_range + + normalized_elevation = np.zeros((width_pixels, length_pixels), dtype=np.float32) + normalized_elevation[ + border_pixels:-border_pixels, + border_pixels:-border_pixels, + ] = inner_normalized + else: + noise_raw = _fractal_perlin_noise_2d( + width_pixels, + length_pixels, + rng, + octaves=self.octaves, + persistence=self.persistence, + lacunarity=self.lacunarity, + scale=effective_scale, + ) + noise_min, noise_max = noise_raw.min(), noise_raw.max() + noise_range = noise_max - noise_min if noise_max > noise_min else 1.0 + normalized_elevation = ((noise_raw - noise_min) / noise_range).astype(np.float32) + + max_physical_height = target_height + base_thickness = max_physical_height * self.base_thickness_ratio + + unique_id = uuid.uuid4().hex + field = spec.add_hfield( + name=f"hfield_{unique_id}", + size=[ + self.size[0] / 2, + self.size[1] / 2, + max_physical_height, + base_thickness, + ], + nrow=normalized_elevation.shape[0], + ncol=normalized_elevation.shape[1], + userdata=normalized_elevation.flatten().tolist(), + ) + + material_name = color_by_height( + spec, normalized_elevation, unique_id, normalized_elevation + ) + + hfield_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_HFIELD, + hfieldname=field.name, + pos=[ + self.size[0] / 2, + self.size[1] / 2, + 0, + ], + material=material_name, + ) + + spawn_height = max_physical_height + origin = np.array([self.size[0] / 2, self.size[1] / 2, spawn_height]) + + # For flat patches, we pass the absolute physical heights. + flat_patches = _compute_flat_patches( + normalized_elevation * max_physical_height, + 1.0, # vertical_scale is 1.0 because we already have physical heights + grid_spacing, + 0, + self.flat_patch_sampling, + rng, + ) + + geom = TerrainGeometry(geom=hfield_geom, hfield=field) + return TerrainOutput(origin=origin, geometries=[geom], flat_patches=flat_patches) diff --git a/mjlab/src/mjlab/terrains/primitive_terrains.py b/mjlab/src/mjlab/terrains/primitive_terrains.py new file mode 100644 index 0000000000000000000000000000000000000000..56bf4fd367a69587ed22c50b6877904dc4c91031 --- /dev/null +++ b/mjlab/src/mjlab/terrains/primitive_terrains.py @@ -0,0 +1,1672 @@ +"""Terrains composed of primitive geometries. + +This module provides terrain generation functionality using primitive geometries, +adapted from the IsaacLab terrain generation system. + +References: + IsaacLab mesh terrain implementation: + https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab/isaaclab/terrains/trimesh/mesh_terrains.py +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import Tuple + +import mujoco +import numpy as np + +from mjlab.terrains.terrain_generator import ( + SubTerrainCfg, + TerrainGeometry, + TerrainOutput, +) +from mjlab.terrains.utils import make_border, make_plane +from mjlab.utils.color import ( + HSV, + brand_ramp, + clamp, + darken_rgba, + hsv_to_rgb, + rgb_to_hsv, +) + +_MUJOCO_BLUE = (0.20, 0.45, 0.95) +_MUJOCO_RED = (0.90, 0.30, 0.30) +_MUJOCO_GREEN = (0.25, 0.80, 0.45) + + +def _get_platform_color( + base_rgb: Tuple[float, float, float], + desaturation_factor: float = 0.4, + lightening_factor: float = 0.25, +) -> Tuple[float, float, float, float]: + hsv = rgb_to_hsv(base_rgb) + new_s = hsv.s * desaturation_factor + new_v = clamp(hsv.v + lightening_factor) + new_hsv = HSV(hsv.h, new_s, new_v) + r, g, b = hsv_to_rgb(new_hsv) + return (r, g, b, 1.0) + + +@dataclass(kw_only=True) +class BoxFlatTerrainCfg(SubTerrainCfg): + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + del difficulty, rng # Unused. + body = spec.body("terrain") + origin = (self.size[0] / 2, self.size[1] / 2, 0.0) + boxes = make_plane(body, self.size, 0.0, center_zero=False) + box_colors = [(0.5, 0.5, 0.5, 1.0)] + geometry = TerrainGeometry(geom=boxes[0], color=box_colors[0]) + return TerrainOutput(origin=np.array(origin), geometries=[geometry]) + + +@dataclass(kw_only=True) +class BoxPyramidStairsTerrainCfg(SubTerrainCfg): + """Configuration for a pyramid stairs terrain.""" + + border_width: float = 0.0 + """Width of the flat border frame around the staircase, in meters. Ignored + when holes is True.""" + step_height_range: tuple[float, float] + """Min and max step height, in meters. Interpolated by difficulty.""" + step_width: float + """Depth (run) of each step, in meters.""" + platform_width: float = 1.0 + """Side length of the flat square platform at the top of the staircase, in meters.""" + holes: bool = False + """If True, steps form a cross pattern with empty gaps in the corners.""" + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + del rng # Unused. + boxes = [] + box_colors = [] + + body = spec.body("terrain") + + step_height = self.step_height_range[0] + difficulty * ( + self.step_height_range[1] - self.step_height_range[0] + ) + + # Compute number of steps in x and y direction. + num_steps_x = int( + (self.size[0] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps_y = int( + (self.size[1] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps = max(0, int(min(num_steps_x, num_steps_y))) + + first_step_rgba = brand_ramp(_MUJOCO_BLUE, 0.0) + border_rgba = darken_rgba(first_step_rgba, 0.85) + + if self.border_width > 0.0 and not self.holes: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], -step_height / 2) + border_inner_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + border_boxes = make_border( + body, self.size, border_inner_size, step_height, border_center + ) + boxes.extend(border_boxes) + for _ in range(len(border_boxes)): + box_colors.append(border_rgba) + + terrain_center = [0.5 * self.size[0], 0.5 * self.size[1], 0.0] + terrain_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + rgba = brand_ramp(_MUJOCO_BLUE, 0.5) + for k in range(num_steps): + t = k / max(num_steps - 1, 1) + rgba = brand_ramp(_MUJOCO_BLUE, t) + for _ in range(4): + box_colors.append(rgba) + + if self.holes: + box_size = (self.platform_width, self.platform_width) + else: + box_size = ( + terrain_size[0] - 2 * k * self.step_width, + terrain_size[1] - 2 * k * self.step_width, + ) + box_z = terrain_center[2] + k * step_height / 2.0 + box_offset = (k + 0.5) * self.step_width + box_height = (k + 2) * step_height + + box_dims = (box_size[0], self.step_width, box_height) + + safe_size = ( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ) + + # Top. + box_pos = ( + terrain_center[0], + terrain_center[1] + terrain_size[1] / 2.0 - box_offset, + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Bottom. + box_pos = ( + terrain_center[0], + terrain_center[1] - terrain_size[1] / 2.0 + box_offset, + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + if self.holes: + box_dims = (self.step_width, box_size[1], box_height) + else: + box_dims = ( + self.step_width, + box_size[1] - 2 * self.step_width, + box_height, + ) + safe_size = ( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ) + + # Right. + box_pos = ( + terrain_center[0] + terrain_size[0] / 2.0 - box_offset, + terrain_center[1], + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Left. + box_pos = ( + terrain_center[0] - terrain_size[0] / 2.0 + box_offset, + terrain_center[1], + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Generate final box for the middle of the terrain. + box_dims = ( + terrain_size[0] - 2 * num_steps * self.step_width, + terrain_size[1] - 2 * num_steps * self.step_width, + (num_steps + 2) * step_height, + ) + box_pos = ( + terrain_center[0], + terrain_center[1], + terrain_center[2] + num_steps * step_height / 2, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ), + pos=box_pos, + ) + boxes.append(box) + origin = np.array( + [terrain_center[0], terrain_center[1], (num_steps + 1) * step_height] + ) + box_colors.append(rgba) + + geometries = [ + TerrainGeometry(geom=box, color=color) + for box, color in zip(boxes, box_colors, strict=True) + ] + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxInvertedPyramidStairsTerrainCfg(BoxPyramidStairsTerrainCfg): + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + del rng # Unused. + boxes = [] + box_colors = [] + + body = spec.body("terrain") + + step_height = self.step_height_range[0] + difficulty * ( + self.step_height_range[1] - self.step_height_range[0] + ) + + # Compute number of steps in x and y direction. + num_steps_x = int( + (self.size[0] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps_y = int( + (self.size[1] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps = max(0, int(min(num_steps_x, num_steps_y))) + total_height = (num_steps + 1) * step_height + + first_step_rgba = brand_ramp(_MUJOCO_RED, 0.0) + border_rgba = darken_rgba(first_step_rgba, 0.85) + + if self.border_width > 0.0 and not self.holes: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], -0.5 * step_height) + border_inner_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + border_boxes = make_border( + body, self.size, border_inner_size, step_height, border_center + ) + boxes.extend(border_boxes) + for _ in range(len(border_boxes)): + box_colors.append(border_rgba) + + terrain_center = [0.5 * self.size[0], 0.5 * self.size[1], 0.0] + terrain_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + + rgba = brand_ramp(_MUJOCO_RED, 0.5) + for k in range(num_steps): + t = k / max(num_steps - 1, 1) + rgba = brand_ramp(_MUJOCO_RED, t) + for _ in range(4): + box_colors.append(rgba) + + if self.holes: + box_size = (self.platform_width, self.platform_width) + else: + box_size = ( + terrain_size[0] - 2 * k * self.step_width, + terrain_size[1] - 2 * k * self.step_width, + ) + + box_z = terrain_center[2] - total_height / 2 - (k + 1) * step_height / 2.0 + box_offset = (k + 0.5) * self.step_width + box_height = total_height - (k + 1) * step_height + + box_dims = (box_size[0], self.step_width, box_height) + safe_size = ( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ) + + # Top. + box_pos = ( + terrain_center[0], + terrain_center[1] + terrain_size[1] / 2.0 - box_offset, + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Bottom. + box_pos = ( + terrain_center[0], + terrain_center[1] - terrain_size[1] / 2.0 + box_offset, + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + if self.holes: + box_dims = (self.step_width, box_size[1], box_height) + else: + box_dims = ( + self.step_width, + box_size[1] - 2 * self.step_width, + box_height, + ) + safe_size = ( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ) + + # Right. + box_pos = ( + terrain_center[0] + terrain_size[0] / 2.0 - box_offset, + terrain_center[1], + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Left. + box_pos = ( + terrain_center[0] - terrain_size[0] / 2.0 + box_offset, + terrain_center[1], + box_z, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=safe_size, + pos=box_pos, + ) + boxes.append(box) + + # Generate final box for the middle of the terrain. + box_dims = ( + terrain_size[0] - 2 * num_steps * self.step_width, + terrain_size[1] - 2 * num_steps * self.step_width, + step_height, + ) + box_pos = ( + terrain_center[0], + terrain_center[1], + terrain_center[2] - total_height - step_height / 2, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_dims[0] / 2.0), + np.maximum(1e-6, box_dims[1] / 2.0), + np.maximum(1e-6, box_dims[2] / 2.0), + ), + pos=box_pos, + ) + boxes.append(box) + origin = np.array( + [terrain_center[0], terrain_center[1], -(num_steps + 1) * step_height] + ) + box_colors.append(rgba) + + geometries = [ + TerrainGeometry(geom=box, color=color) + for box, color in zip(boxes, box_colors, strict=True) + ] + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxRandomGridTerrainCfg(SubTerrainCfg): + grid_width: float + """Side length of each square grid cell, in meters.""" + grid_height_range: tuple[float, float] + """Min and max grid cell height bound, in meters. Interpolated by difficulty. + At a given difficulty, cell heights are sampled uniformly from + [-bound, +bound].""" + platform_width: float = 1.0 + """Side length of the flat square platform at the grid center, in meters.""" + holes: bool = False + """If True, only the cross-shaped region around the center platform has grid cells.""" + merge_similar_heights: bool = False + """If True, adjacent cells with similar heights are merged into larger boxes + to reduce geom count.""" + height_merge_threshold: float = 0.05 + """Maximum height difference between cells that can be merged, in meters.""" + max_merge_distance: int = 3 + """Maximum number of grid cells that can be merged in each direction.""" + border_width: float = 0.25 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + if self.size[0] != self.size[1]: + raise ValueError(f"The terrain must be square. Received size: {self.size}.") + + grid_height = self.grid_height_range[0] + difficulty * ( + self.grid_height_range[1] - self.grid_height_range[0] + ) + + body = spec.body("terrain") + + boxes_list = [] + box_colors = [] + + num_boxes_x = int((self.size[0] - 2 * self.border_width) / self.grid_width) + num_boxes_y = int((self.size[1] - 2 * self.border_width) / self.grid_width) + + terrain_height = 1.0 + border_width = self.size[0] - min(num_boxes_x, num_boxes_y) * self.grid_width + + if border_width <= 0: + raise RuntimeError( + "Border width must be greater than 0! Adjust the parameter 'self.grid_width'." + ) + + border_thickness = border_width / 2 + border_center_z = -terrain_height / 2 + + half_size = self.size[0] / 2 + half_border = border_thickness / 2 + half_terrain = terrain_height / 2 + + first_step_rgba = brand_ramp(_MUJOCO_GREEN, 0.0) + border_rgba = darken_rgba(first_step_rgba, 0.85) + + border_specs = [ + ( + (half_size, half_border, half_terrain), + (half_size, self.size[1] - half_border, border_center_z), + ), + ( + (half_size, half_border, half_terrain), + (half_size, half_border, border_center_z), + ), + ( + (half_border, (self.size[1] - 2 * border_thickness) / 2, half_terrain), + (half_border, half_size, border_center_z), + ), + ( + (half_border, (self.size[1] - 2 * border_thickness) / 2, half_terrain), + (self.size[0] - half_border, half_size, border_center_z), + ), + ] + + for size, pos in border_specs: + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=size, + pos=pos, + ) + boxes_list.append(box) + box_colors.append(border_rgba) + + height_map = rng.uniform(-grid_height, grid_height, (num_boxes_x, num_boxes_y)) + + if self.merge_similar_heights and not self.holes: + box_list_, box_color_ = self._create_merged_boxes( + body, + height_map, + num_boxes_x, + num_boxes_y, + grid_height, + terrain_height, + border_width, + ) + boxes_list.extend(box_list_) + box_colors.extend(box_color_) + else: + box_list_, box_color_ = self._create_individual_boxes( + body, + height_map, + num_boxes_x, + num_boxes_y, + grid_height, + terrain_height, + border_width, + ) + boxes_list.extend(box_list_) + box_colors.extend(box_color_) + + # Platform + platform_height = terrain_height + grid_height + platform_center_z = -terrain_height / 2 + grid_height / 2 + half_platform = self.platform_width / 2 + + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(half_platform, half_platform, platform_height / 2), + pos=(self.size[0] / 2, self.size[1] / 2, platform_center_z), + ) + boxes_list.append(box) + platform_rgba = _get_platform_color(_MUJOCO_GREEN) + box_colors.append(platform_rgba) + + origin = np.array([self.size[0] / 2, self.size[1] / 2, grid_height]) + + geometries = [ + TerrainGeometry(geom=box, color=color) + for box, color in zip(boxes_list, box_colors, strict=True) + ] + return TerrainOutput(origin=origin, geometries=geometries) + + def _create_merged_boxes( + self, + body, + height_map, + num_boxes_x, + num_boxes_y, + grid_height, + terrain_height, + border_width, + ): + """Create merged boxes for similar heights to reduce geom count.""" + boxes = [] + box_colors = [] + visited = np.zeros((num_boxes_x, num_boxes_y), dtype=bool) + + half_border_width = border_width / 2 + neg_half_terrain = -terrain_height / 2 + + # Quantize heights to create more merging opportunities + quantized_heights = ( + np.round(height_map / self.height_merge_threshold) * self.height_merge_threshold + ) + + for i in range(num_boxes_x): + for j in range(num_boxes_y): + if visited[i, j]: + continue + + # Find rectangular region with similar height + height = quantized_heights[i, j] + + normalized_height = (height + grid_height) / (2 * grid_height) + t = float(np.clip(normalized_height, 0.0, 1.0)) + rgba = brand_ramp(_MUJOCO_GREEN, t) + + # Greedy expansion in x and y directions + max_x = i + 1 + max_y = j + 1 + + # Try to expand in x direction first + while max_x < min(i + self.max_merge_distance, num_boxes_x): + if not visited[max_x, j] and abs(quantized_heights[max_x, j] - height) < 1e-6: + max_x += 1 + else: + break + + # Then expand in y direction for the found x range + can_expand_y = True + while max_y < min(j + self.max_merge_distance, num_boxes_y) and can_expand_y: + for x in range(i, max_x): + if visited[x, max_y] or abs(quantized_heights[x, max_y] - height) > 1e-6: + can_expand_y = False + break + if can_expand_y: + max_y += 1 + + # Mark region as visited + visited[i:max_x, j:max_y] = True + + # Create merged box + width_x = (max_x - i) * self.grid_width + width_y = (max_y - j) * self.grid_width + + box_center_x = half_border_width + (i + (max_x - i) / 2) * self.grid_width + box_center_y = half_border_width + (j + (max_y - j) / 2) * self.grid_width + + box_height = terrain_height + height + box_center_z = neg_half_terrain + height / 2 + + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(width_x / 2, width_y / 2, box_height / 2), + pos=(box_center_x, box_center_y, box_center_z), + ) + boxes.append(box) + box_colors.append(rgba) + + return boxes, box_colors + + def _create_individual_boxes( + self, + body, + height_map, + num_boxes_x, + num_boxes_y, + grid_height, + terrain_height, + border_width, + ): + """Original approach with individual boxes.""" + boxes = [] + box_colors = [] + half_grid = self.grid_width / 2 + half_border_width = border_width / 2 + neg_half_terrain = -terrain_height / 2 + + if self.holes: + platform_half = self.platform_width / 2 + terrain_center = self.size[0] / 2 + platform_min = terrain_center - platform_half + platform_max = terrain_center + platform_half + else: + platform_min = None + platform_max = None + + for i in range(num_boxes_x): + box_center_x = half_border_width + (i + 0.5) * self.grid_width + + if self.holes and not (platform_min <= box_center_x <= platform_max): + in_y_strip = False + else: + in_y_strip = True + + for j in range(num_boxes_y): + box_center_y = half_border_width + (j + 0.5) * self.grid_width + + if self.holes: + in_x_strip = platform_min <= box_center_y <= platform_max + if not (in_x_strip or in_y_strip): + continue + + height_noise = height_map[i, j] + box_height = terrain_height + height_noise + box_center_z = neg_half_terrain + height_noise / 2 + + normalized_height = (height_noise + grid_height) / (2 * grid_height) + t = float(np.clip(normalized_height, 0.0, 1.0)) + rgba = brand_ramp(_MUJOCO_GREEN, t) + box_colors.append(rgba) + + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(half_grid, half_grid, box_height / 2), + pos=(box_center_x, box_center_y, box_center_z), + ) + boxes.append(box) + + return boxes, box_colors + + +@dataclass(kw_only=True) +class BoxRandomSpreadTerrainCfg(SubTerrainCfg): + num_boxes: int = 60 + box_width_range: tuple[float, float] = (0.3, 1.0) + box_length_range: tuple[float, float] = (0.3, 1.0) + box_height_range: tuple[float, float] = (0.05, 1.0) + box_yaw_range: tuple[float, float] = (0, 360) + add_floor: bool = True + platform_width: float = 1.0 + border_width: float = 0.25 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Scale number of boxes by difficulty. + num_boxes = int(self.num_boxes * (0.5 + 0.5 * difficulty)) + + terrain_height = 1.0 + border_rgba = darken_rgba(brand_ramp(_MUJOCO_BLUE, 0.0), 0.85) + + if self.border_width > 0.0: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], -terrain_height / 2) + border_inner_size = ( + np.maximum(1e-6, self.size[0] - 2 * self.border_width), + np.maximum(1e-6, self.size[1] - 2 * self.border_width), + ) + border_boxes = make_border( + body, self.size, border_inner_size, terrain_height, border_center + ) + for box in border_boxes: + geometries.append(TerrainGeometry(geom=box, color=border_rgba)) + + if self.add_floor: + floor_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + (self.size[0] - 2 * self.border_width) / 2, + (self.size[1] - 2 * self.border_width) / 2, + 0.05, + ), + pos=(self.size[0] / 2, self.size[1] / 2, -0.05), + ) + geometries.append(TerrainGeometry(geom=floor_geom, color=(0.4, 0.4, 0.4, 1.0))) + + # Platform + platform_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.platform_width / 2, self.platform_width / 2, terrain_height / 2), + pos=(self.size[0] / 2, self.size[1] / 2, -terrain_height / 2), + ) + geometries.append(TerrainGeometry(geom=platform_geom, color=(0.4, 0.4, 0.4, 1.0))) + + platform_half = self.platform_width / 2 + terrain_center = self.size[0] / 2 + platform_min = terrain_center - platform_half + platform_max = terrain_center + platform_half + + for _ in range(num_boxes): + # Random size. + size_x = rng.uniform(*self.box_width_range) + size_y = rng.uniform(*self.box_length_range) + height = rng.uniform(*self.box_height_range) + + # Scale height by difficulty. + height = height * (0.2 + 0.8 * difficulty) + + # Random position within inner area. + pos_x = rng.uniform( + self.border_width + size_x / 2, self.size[0] - self.border_width - size_x / 2 + ) + pos_y = rng.uniform( + self.border_width + size_y / 2, self.size[1] - self.border_width - size_y / 2 + ) + + # Avoid platform. + if (platform_min - size_x / 2 <= pos_x <= platform_max + size_x / 2) and ( + platform_min - size_y / 2 <= pos_y <= platform_max + size_y / 2 + ): + continue + + pos_z = height / 2 + + # Random orientation (yaw). + yaw = np.deg2rad(rng.uniform(*self.box_yaw_range)) + + rgba = brand_ramp(_MUJOCO_BLUE, rng.uniform(0.3, 0.8)) + + geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, size_x / 2), + np.maximum(1e-6, size_y / 2), + np.maximum(1e-6, height / 2), + ), + pos=(pos_x, pos_y, pos_z), + ) + # MuJoCo quat is (w, x, y, z). + geom.quat = np.array([np.cos(yaw / 2), 0, 0, np.sin(yaw / 2)]) + geometries.append(TerrainGeometry(geom=geom, color=rgba)) + + origin = np.array([self.size[0] / 2, self.size[1] / 2, 0.0]) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxOpenStairsTerrainCfg(SubTerrainCfg): + step_height_range: tuple[float, float] = (0.1, 0.2) + step_width_range: tuple[float, float] = (0.4, 0.8) + platform_width: float = 1.0 + border_width: float = 0.25 + step_thickness: float = 0.05 + inverted: bool = True + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + del rng # Unused. + body = spec.body("terrain") + geometries = [] + + step_height = self.step_height_range[0] + difficulty * ( + self.step_height_range[1] - self.step_height_range[0] + ) + step_width = self.step_width_range[1] - difficulty * ( + self.step_width_range[1] - self.step_width_range[0] + ) + + # Compute number of steps. + num_steps_x = int( + (self.size[0] - 2 * self.border_width - self.platform_width) / (2 * step_width) + ) + num_steps_y = int( + (self.size[1] - 2 * self.border_width - self.platform_width) / (2 * step_width) + ) + num_steps = int(min(num_steps_x, num_steps_y)) + + first_step_rgba = brand_ramp(_MUJOCO_BLUE, 0.0) + border_rgba = darken_rgba(first_step_rgba, 0.85) + + if self.border_width > 0.0: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], -step_height / 2) + border_inner_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + border_boxes = make_border( + body, self.size, border_inner_size, step_height, border_center + ) + for box in border_boxes: + geometries.append(TerrainGeometry(geom=box, color=border_rgba)) + + terrain_center = [0.5 * self.size[0], 0.5 * self.size[1], 0.0] + terrain_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + + rgba = brand_ramp(_MUJOCO_BLUE, 0.5) + for k in range(num_steps): + t = k / max(num_steps - 1, 1) + rgba = brand_ramp(_MUJOCO_BLUE, t) + + box_size = ( + terrain_size[0] - 2 * k * step_width, + terrain_size[1] - 2 * k * step_width, + ) + + # Inverted: Outer steps (small k) are higher (Bowl). + # Normal: Inner steps (large k) are higher (Pyramid). + if self.inverted: + # Highest step (k=0) top is at 0 (border height). + z_pos = -k * step_height - 0.5 * self.step_thickness + else: + # Lowest step (k=0) top is at step_height. + z_pos = (k + 1) * step_height - 0.5 * self.step_thickness + + box_offset = (k + 0.5) * step_width + + # Top. + box_pos = ( + terrain_center[0], + terrain_center[1] + terrain_size[1] / 2.0 - box_offset, + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_size[0] / 2.0), + np.maximum(1e-6, step_width / 2.0), + self.step_thickness / 2.0, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Bottom. + box_pos = ( + terrain_center[0], + terrain_center[1] - terrain_size[1] / 2.0 + box_offset, + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_size[0] / 2.0), + np.maximum(1e-6, step_width / 2.0), + self.step_thickness / 2.0, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Right. + box_pos = ( + terrain_center[0] + terrain_size[0] / 2.0 - box_offset, + terrain_center[1], + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, step_width / 2.0), + np.maximum(1e-6, (box_size[1] - 2 * step_width) / 2.0), + self.step_thickness / 2.0, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Left. + box_pos = ( + terrain_center[0] - terrain_size[0] / 2.0 + box_offset, + terrain_center[1], + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, step_width / 2.0), + np.maximum(1e-6, (box_size[1] - 2 * step_width) / 2.0), + self.step_thickness / 2.0, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Platform. + platform_size = ( + np.maximum(1e-6, terrain_size[0] - 2 * num_steps * step_width), + np.maximum(1e-6, terrain_size[1] - 2 * num_steps * step_width), + ) + # Bowl: Align bottom (ground level). + # Bowl: Highest step is border level. Platform is at bottom. + # Pyramid: Align top-most level. + if self.inverted: + platform_h_center = -num_steps * step_height - 0.5 * self.step_thickness + else: + platform_h_center = (num_steps + 1) * step_height - 0.5 * self.step_thickness + + platform_pos = (terrain_center[0], terrain_center[1], platform_h_center) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(platform_size[0] / 2.0, platform_size[1] / 2.0, self.step_thickness / 2.0), + pos=platform_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + origin = np.array( + [ + terrain_center[0], + terrain_center[1], + platform_h_center + self.step_thickness / 2.0, + ] + ) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxRandomStairsTerrainCfg(SubTerrainCfg): + step_width: float = 0.8 + step_height_range: tuple[float, float] = (0.1, 0.3) + platform_width: float = 1.0 + border_width: float = 0.25 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Compute number of steps. + num_steps_x = int( + (self.size[0] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps_y = int( + (self.size[1] - 2 * self.border_width - self.platform_width) + / (2 * self.step_width) + ) + num_steps = int(min(num_steps_x, num_steps_y)) + + first_step_rgba = brand_ramp(_MUJOCO_BLUE, 0.0) + border_rgba = darken_rgba(first_step_rgba, 0.85) + + if self.border_width > 0.0: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], -0.05) + border_inner_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + border_boxes = make_border(body, self.size, border_inner_size, 0.1, border_center) + for box in border_boxes: + geometries.append(TerrainGeometry(geom=box, color=border_rgba)) + + terrain_center = [0.5 * self.size[0], 0.5 * self.size[1], 0.0] + terrain_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + + rgba = brand_ramp(_MUJOCO_BLUE, 0.5) + current_z = 0.0 + for k in range(num_steps): + t = k / max(num_steps - 1, 1) + rgba = brand_ramp(_MUJOCO_BLUE, t) + + h_low, h_high = self.step_height_range + step_h = rng.uniform(h_low, h_high) * (0.5 + 0.5 * difficulty) + total_h = current_z + step_h + + box_size = ( + terrain_size[0] - 2 * k * self.step_width, + terrain_size[1] - 2 * k * self.step_width, + ) + + z_pos = total_h / 2 + box_offset = (k + 0.5) * self.step_width + + # Top. + box_pos = ( + terrain_center[0], + terrain_center[1] + terrain_size[1] / 2.0 - box_offset, + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_size[0] / 2.0), + np.maximum(1e-6, self.step_width / 2.0), + np.maximum(1e-6, total_h / 2.0), + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Bottom. + box_pos = ( + terrain_center[0], + terrain_center[1] - terrain_size[1] / 2.0 + box_offset, + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, box_size[0] / 2.0), + np.maximum(1e-6, self.step_width / 2.0), + np.maximum(1e-6, total_h / 2.0), + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Right. + box_pos = ( + terrain_center[0] + terrain_size[0] / 2.0 - box_offset, + terrain_center[1], + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, self.step_width / 2.0), + np.maximum(1e-6, (box_size[1] - 2 * self.step_width) / 2.0), + np.maximum(1e-6, total_h / 2.0), + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Left. + box_pos = ( + terrain_center[0] - terrain_size[0] / 2.0 + box_offset, + terrain_center[1], + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, self.step_width / 2.0), + np.maximum(1e-6, (box_size[1] - 2 * self.step_width) / 2.0), + np.maximum(1e-6, total_h / 2.0), + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + current_z = total_h + + # Platform + platform_size = ( + np.maximum(1e-6, terrain_size[0] - 2 * num_steps * self.step_width), + np.maximum(1e-6, terrain_size[1] - 2 * num_steps * self.step_width), + ) + platform_pos = (terrain_center[0], terrain_center[1], current_z / 2) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + platform_size[0] / 2.0, + platform_size[1] / 2.0, + np.maximum(1e-6, current_z / 2.0), + ), + pos=platform_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + origin = np.array([terrain_center[0], terrain_center[1], current_z]) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxSteppingStonesTerrainCfg(SubTerrainCfg): + stone_size_range: tuple[float, float] = (0.4, 0.8) + stone_distance_range: tuple[float, float] = (0.2, 0.5) + stone_height: float = 0.2 + stone_height_variation: float = 0.1 + stone_size_variation: float = 0.1 + floor_depth: float = 2.0 + displacement_range: float = 0.1 + platform_width: float = 1.0 + border_width: float = 0.25 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Difficulty-scaled variations. + stone_size_variation = self.stone_size_variation * difficulty + displacement_range = self.displacement_range * difficulty + stone_height_variation = self.stone_height_variation * difficulty + + # Increase distance between stones with difficulty. + d_low, d_high = self.stone_distance_range + avg_distance = (d_low + d_high) / 2 + difficulty * (d_high - d_low) / 2 + + # Grid spacing (stone size + gap). + avg_stone_size = (self.stone_size_range[0] + self.stone_size_range[1]) / 2 + spacing = avg_stone_size + avg_distance + + # Aggressive grid density to reach borders. + inner_w = self.size[0] - 2 * self.border_width + inner_h = self.size[1] - 2 * self.border_width + num_x = int(np.floor(inner_w / spacing)) + 1 + num_y = int(np.floor(inner_h / spacing)) + 1 + + offset_x = self.border_width + (inner_w - (num_x - 1) * spacing) / 2 + offset_y = self.border_width + (inner_h - (num_y - 1) * spacing) / 2 + + border_rgba = darken_rgba(brand_ramp(_MUJOCO_GREEN, 0.0), 0.85) + z_center = (self.stone_height - self.floor_depth) / 2 + half_height = (self.stone_height + self.floor_depth) / 2 + + if self.border_width > 0.0: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], z_center) + border_boxes = make_border( + body, + self.size, + (self.size[0] - 2 * self.border_width, self.size[1] - 2 * self.border_width), + self.stone_height + self.floor_depth, + border_center, + ) + for b_geom in border_boxes: + geometries.append(TerrainGeometry(geom=b_geom, color=border_rgba)) + + # Ground floor (deep pit). + floor_h = 0.1 + floor_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.size[0] / 2, self.size[1] / 2, floor_h / 2), + pos=(self.size[0] / 2, self.size[1] / 2, -self.floor_depth - floor_h / 2), + ) + geometries.append(TerrainGeometry(geom=floor_geom, color=(0.1, 0.1, 0.1, 1.0))) + + # Platform Column. + platform_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, self.platform_width / 2), + np.maximum(1e-6, self.platform_width / 2), + np.maximum(1e-6, half_height), + ), + pos=(self.size[0] / 2, self.size[1] / 2, z_center), + ) + geometries.append( + TerrainGeometry(geom=platform_geom, color=brand_ramp(_MUJOCO_GREEN, 0.5)) + ) + + platform_half = self.platform_width / 2 + terrain_center = self.size[0] / 2 + platform_min = terrain_center - platform_half + platform_max = terrain_center + platform_half + + inner_min_x, inner_max_x = self.border_width, self.size[0] - self.border_width + inner_min_y, inner_max_y = self.border_width, self.size[1] - self.border_width + + for i in range(num_x): + for j in range(num_y): + avg_s_min, avg_s_max = self.stone_size_range + base_size = (avg_s_min + avg_s_max) / 2 + + # Proposed position with displacement. + px = ( + offset_x + i * spacing + rng.uniform(-displacement_range, displacement_range) + ) + py = ( + offset_y + j * spacing + rng.uniform(-displacement_range, displacement_range) + ) + + # Randomized size. + size_x = base_size + rng.uniform(-stone_size_variation, stone_size_variation) + size_y = base_size + rng.uniform(-stone_size_variation, stone_size_variation) + + # Initial bounds. + x_min, x_max = px - size_x / 2, px + size_x / 2 + y_min, y_max = py - size_y / 2, py + size_y / 2 + + # Avoid platform. + margin = max(avg_s_max, self.stone_size_variation * 2) / 2 + if (platform_min - margin <= px <= platform_max + margin) and ( + platform_min - margin <= py <= platform_max + margin + ): + continue + + # Final clip against border. + x_min = np.clip(x_min, inner_min_x, inner_max_x) + x_max = np.clip(x_max, inner_min_x, inner_max_x) + y_min = np.clip(y_min, inner_min_y, inner_max_y) + y_max = np.clip(y_max, inner_min_y, inner_max_y) + + clipped_sx = x_max - x_min + clipped_sy = y_max - y_min + clipped_px = (x_min + x_max) / 2 + clipped_py = (y_min + y_max) / 2 + + if clipped_sx < 0.05 or clipped_sy < 0.05: + continue + + # Stones grow from the floor up to around ground level. + h = ( + self.floor_depth + + self.stone_height + + rng.uniform(-stone_height_variation, stone_height_variation) + ) + pos_z = -self.floor_depth + h / 2 + + rgba = brand_ramp(_MUJOCO_GREEN, rng.uniform(0.4, 0.7)) + + geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, clipped_sx / 2), + np.maximum(1e-6, clipped_sy / 2), + np.maximum(1e-6, h / 2), + ), + pos=(clipped_px, clipped_py, pos_z), + ) + geometries.append(TerrainGeometry(geom=geom, color=rgba)) + + origin = np.array([self.size[0] / 2, self.size[1] / 2, self.stone_height]) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxNarrowBeamsTerrainCfg(SubTerrainCfg): + num_beams: int = 16 + beam_width_range: tuple[float, float] = (0.2, 0.4) + beam_height: float = 0.2 + spacing: float = 0.8 + platform_width: float = 1.0 + border_width: float = 0.25 + floor_depth: float = 2.0 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Number of beams can be increased with difficulty if desired. + num_beams = int(self.num_beams) + + # Narrower beams with difficulty (interp from max to min). + w_min, w_max = self.beam_width_range + beam_width = w_max - difficulty * (w_max - w_min) + + border_rgba = darken_rgba(brand_ramp(_MUJOCO_BLUE, 0.0), 0.85) + z_center = (self.beam_height - self.floor_depth) / 2 + half_height = (self.beam_height + self.floor_depth) / 2 + + if self.border_width > 0.0: + border_center = (0.5 * self.size[0], 0.5 * self.size[1], z_center) + border_boxes = make_border( + body, + self.size, + (self.size[0] - 2 * self.border_width, self.size[1] - 2 * self.border_width), + self.beam_height + self.floor_depth, + border_center, + ) + for b_geom in border_boxes: + geometries.append(TerrainGeometry(geom=b_geom, color=border_rgba)) + + # Ground floor (deep pit). + floor_h = 0.1 + floor_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.size[0] / 2, self.size[1] / 2, floor_h / 2), + pos=(self.size[0] / 2, self.size[1] / 2, -self.floor_depth - floor_h / 2), + ) + geometries.append(TerrainGeometry(geom=floor_geom, color=(0.1, 0.1, 0.1, 1.0))) + + # Platform Column. Top at beam_height. + platform_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, self.platform_width / 2), + np.maximum(1e-6, self.platform_width / 2), + np.maximum(1e-6, half_height), + ), + pos=(self.size[0] / 2, self.size[1] / 2, z_center), + ) + geometries.append( + TerrainGeometry(geom=platform_geom, color=brand_ramp(_MUJOCO_BLUE, 0.5)) + ) + + inner_size = self.size[0] - 2 * self.border_width + center_x, center_y = self.size[0] / 2, self.size[1] / 2 + platform_radius = self.platform_width / 2 + + # Radial beams as columns. + angles = np.linspace(0, 2 * np.pi, num_beams, endpoint=False) + for angle in angles: + # Distance to the square border at this angle. + # r = (L/2) / max(|cos(theta)|, |sin(theta)|) + cos_a = abs(np.cos(angle)) + sin_a = abs(np.sin(angle)) + dist_to_border = (inner_size / 2) / max(cos_a, sin_a) + + # Additional length so that the farthest corner reaches the border. + # delta_L = (w/2) * tan(local_theta) = (w/2) * min(cos, sin) / max(cos, sin) + extra_length = (beam_width / 2) * min(cos_a, sin_a) / max(cos_a, sin_a) + + beam_length = dist_to_border + extra_length - platform_radius + + dist_to_center = platform_radius + beam_length / 2 + px = center_x + dist_to_center * np.cos(angle) + py = center_y + dist_to_center * np.sin(angle) + pz = z_center + + geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, beam_length / 2), + np.maximum(1e-6, beam_width / 2), + np.maximum(1e-6, half_height), + ), + pos=(px, py, pz), + ) + # Quat for yaw = angle. + geom.quat = np.array([np.cos(angle / 2), 0, 0, np.sin(angle / 2)]) + geometries.append(TerrainGeometry(geom=geom, color=brand_ramp(_MUJOCO_BLUE, 0.5))) + + origin = np.array([self.size[0] / 2, self.size[1] / 2, self.beam_height]) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxTiltedGridTerrainCfg(SubTerrainCfg): + grid_width: float = 1.0 + tilt_range_deg: float = 15.0 + height_range: float = 0.1 + platform_width: float = 1.0 + border_width: float = 0.25 + floor_depth: float = 2.0 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Difficulty-scaled variations. + max_tilt = np.deg2rad(self.tilt_range_deg * difficulty) + actual_range = self.height_range * difficulty + + # Logic adopted from BoxRandomGridTerrainCfg for consistent alignment. + num_boxes_x = int((self.size[0] - 2 * self.border_width) / self.grid_width) + num_boxes_y = int((self.size[1] - 2 * self.border_width) / self.grid_width) + + border_actual = self.size[0] - num_boxes_x * self.grid_width + half_border = border_actual / 2 + + border_rgba = darken_rgba(brand_ramp(_MUJOCO_GREEN, 0.0), 0.85) + base_h = 0.2 + z_center = (base_h - self.floor_depth) / 2 + half_height = (base_h + self.floor_depth) / 2 + + # Border. + if border_actual > 0: + border_center = (self.size[0] / 2, self.size[1] / 2, z_center) + border_boxes = make_border( + body, + self.size, + (num_boxes_x * self.grid_width, num_boxes_y * self.grid_width), + base_h + self.floor_depth, + border_center, + ) + for b_geom in border_boxes: + geometries.append(TerrainGeometry(geom=b_geom, color=border_rgba)) + + # Ground floor. + floor_h = 0.1 + floor_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.size[0] / 2, self.size[1] / 2, floor_h / 2), + pos=(self.size[0] / 2, self.size[1] / 2, -self.floor_depth - floor_h / 2), + ) + geometries.append(TerrainGeometry(geom=floor_geom, color=(0.1, 0.1, 0.1, 1.0))) + + # Platform. + platform_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.platform_width / 2, self.platform_width / 2, half_height), + pos=(self.size[0] / 2, self.size[1] / 2, z_center), + ) + geometries.append( + TerrainGeometry(geom=platform_geom, color=brand_ramp(_MUJOCO_GREEN, 0.5)) + ) + + platform_half = self.platform_width / 2 + terrain_center = self.size[0] / 2 + platform_min = terrain_center - platform_half + platform_max = terrain_center + platform_half + + for i in range(num_boxes_x): + bx_center = half_border + (i + 0.5) * self.grid_width + for j in range(num_boxes_y): + by_center = half_border + (j + 0.5) * self.grid_width + + # Skip if inside platform. + if (platform_min <= bx_center <= platform_max) and ( + platform_min <= by_center <= platform_max + ): + continue + + h_noise = rng.uniform(-actual_range / 2, actual_range / 2) + total_h = base_h + h_noise + + tilt_x = rng.uniform(-max_tilt, max_tilt) + tilt_y = rng.uniform(-max_tilt, max_tilt) + + # Mesh vertices. + # Vertical sides: top and bottom x,y are identical. + x_min, x_max = bx_center - self.grid_width / 2, bx_center + self.grid_width / 2 + y_min, y_max = by_center - self.grid_width / 2, by_center + self.grid_width / 2 + + verts = [] + # Bottom verts 0-3 (at -floor_depth) + for vx in [x_min, x_max]: + for vy in [y_min, y_max]: + verts.append([vx, vy, -self.floor_depth]) + # Top verts 4-7 (tilted) + for vx in [x_min, x_max]: + for vy in [y_min, y_max]: + vz = total_h + tilt_x * (vx - bx_center) + tilt_y * (vy - by_center) + verts.append([vx, vy, vz]) + + # Faces ccw from outside. + # 0:(min,min), 1:(min,max), 2:(max,min), 3:(max,max) + # 4-7 are same x,y as 0-3 but at top. + # fmt: off + faces = [ + 4, 6, 7, 4, 7, 5, # Top (+z) + 0, 1, 3, 0, 3, 2, # Bottom (-z) + 0, 2, 6, 0, 6, 4, # Front (-y) + 1, 5, 7, 1, 7, 3, # Back (+y) + 0, 4, 5, 0, 5, 1, # Left (-x) + 2, 3, 7, 2, 7, 6, # Right (+x) + ] + # fmt: on + + m_name = f"tile_{i}_{j}_{rng.integers(int(1e9))}" + mesh = spec.add_mesh( + name=m_name, + uservert=np.array(verts).flatten().tolist(), + userface=np.array(faces).flatten().tolist(), + ) + + rgba = brand_ramp(_MUJOCO_GREEN, rng.uniform(0.3, 0.7)) + geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_MESH, + meshname=mesh.name, + pos=(0, 0, 0), + ) + geometries.append(TerrainGeometry(geom=geom, color=rgba)) + + origin = np.array([self.size[0] / 2, self.size[1] / 2, base_h]) + return TerrainOutput(origin=origin, geometries=geometries) + + +@dataclass(kw_only=True) +class BoxNestedRingsTerrainCfg(SubTerrainCfg): + num_rings: int = 5 + ring_width_range: tuple[float, float] = (0.3, 0.6) + gap_range: tuple[float, float] = (0.0, 0.2) + height_range: tuple[float, float] = (0.1, 0.4) + platform_width: float = 1.0 + border_width: float = 0.25 + floor_depth: float = 2.0 + + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + body = spec.body("terrain") + geometries = [] + + # Difficulty scaling: wider width range and higher average height. + h_scale = 1.0 + difficulty * 0.5 + w_min, w_max = self.ring_width_range + ring_width = w_max - difficulty * (w_max - w_min) + + border_rgba = darken_rgba(brand_ramp(_MUJOCO_BLUE, 0.0), 0.85) + # Use ground level z=0 as top of border/beams for consistency with NarrowBeams. + # In beam terrain, border top was at beam_height. + + if self.border_width > 0.0: + border_h = 0.5 + border_center = ( + 0.5 * self.size[0], + 0.5 * self.size[1], + (border_h - self.floor_depth) / 2, + ) + border_boxes = make_border( + body, + self.size, + (self.size[0] - 2 * self.border_width, self.size[1] - 2 * self.border_width), + border_h + self.floor_depth, + border_center, + ) + for b_geom in border_boxes: + geometries.append(TerrainGeometry(geom=b_geom, color=border_rgba)) + + # Ground floor (deep pit). + floor_h = 0.1 + floor_geom = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(self.size[0] / 2, self.size[1] / 2, floor_h / 2), + pos=(self.size[0] / 2, self.size[1] / 2, -self.floor_depth - floor_h / 2), + ) + geometries.append(TerrainGeometry(geom=floor_geom, color=(0.1, 0.1, 0.1, 1.0))) + + terrain_center = [0.5 * self.size[0], 0.5 * self.size[1], 0.0] + terrain_size = ( + self.size[0] - 2 * self.border_width, + self.size[1] - 2 * self.border_width, + ) + + current_outer_size = list(terrain_size) + + gap_min, gap_max = self.gap_range + gap = gap_min + difficulty * (gap_max - gap_min) + + for k in range(self.num_rings): + # Ring k: randomized height. + h = rng.uniform(self.height_range[0], self.height_range[1]) * h_scale + + t = k / max(self.num_rings - 1, 1) + rgba = brand_ramp(_MUJOCO_BLUE, t) + + # Outer dimensions of this ring. + ring_outer_size = ( + current_outer_size[0], + current_outer_size[1], + ) + + # Stop if we get too small. + if ( + ring_outer_size[0] <= self.platform_width + or ring_outer_size[1] <= self.platform_width + ): + break + + # Position each ring segment based on current_outer_size. + + half_h = (h + self.floor_depth) / 2 + z_pos = (h - self.floor_depth) / 2 + + # Four segments for the ring. + # Top/Bottom + for dy in [-1, 1]: + box_pos = ( + terrain_center[0], + terrain_center[1] + dy * (ring_outer_size[1] - ring_width) / 2, + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, ring_outer_size[0] / 2.0), + np.maximum(1e-6, ring_width / 2.0), + half_h, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Left/Right + for dx in [-1, 1]: + box_pos = ( + terrain_center[0] + dx * (ring_outer_size[0] - ring_width) / 2, + terrain_center[1], + z_pos, + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=( + np.maximum(1e-6, ring_width / 2.0), + np.maximum(1e-6, (ring_outer_size[1] - 2 * ring_width) / 2.0), + half_h, + ), + pos=box_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=rgba)) + + # Shrink current_outer_size for next ring. + current_outer_size[0] -= 2 * (ring_width + gap) + current_outer_size[1] -= 2 * (ring_width + gap) + + # Center Platform Column matches the remaining hole exactly. + platform_size = ( + np.maximum( + 1e-2, current_outer_size[0] + 2 * gap + ), # Fill the ring hole + gap area. + np.maximum(1e-2, current_outer_size[1] + 2 * gap), + ) + platform_h = 0.2 + + platform_half_h = (platform_h + self.floor_depth) / 2 + platform_z = (platform_h - self.floor_depth) / 2 + + platform_pos = (terrain_center[0], terrain_center[1], platform_z) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(platform_size[0] / 2.0, platform_size[1] / 2.0, platform_half_h), + pos=platform_pos, + ) + geometries.append(TerrainGeometry(geom=box, color=brand_ramp(_MUJOCO_BLUE, 0.5))) + + origin = np.array([terrain_center[0], terrain_center[1], platform_h]) + return TerrainOutput(origin=origin, geometries=geometries) diff --git a/mjlab/src/mjlab/terrains/terrain_generator.py b/mjlab/src/mjlab/terrains/terrain_generator.py new file mode 100644 index 0000000000000000000000000000000000000000..006d2b102da5d8fca7d4b33caa0a30a5e8a0f975 --- /dev/null +++ b/mjlab/src/mjlab/terrains/terrain_generator.py @@ -0,0 +1,383 @@ +from __future__ import annotations + +import abc +import time +from dataclasses import dataclass, field +from typing import Literal + +import mujoco +import numpy as np + +from mjlab.terrains.utils import make_border +from mjlab.utils.color import RGBA + +_DARK_GRAY = (0.2, 0.2, 0.2, 1.0) + + +@dataclass +class FlatPatchSamplingCfg: + """Configuration for sampling flat patches on a heightfield surface.""" + + num_patches: int = 10 + """Number of flat patches to sample per sub-terrain.""" + patch_radius: float = 0.5 + """Radius of the circular footprint used to test flatness, in meters.""" + max_height_diff: float = 0.05 + """Maximum allowed height variation within the patch footprint, in meters.""" + x_range: tuple[float, float] = (-1e6, 1e6) + """Allowed range of x coordinates for sampled patches, in meters.""" + y_range: tuple[float, float] = (-1e6, 1e6) + """Allowed range of y coordinates for sampled patches, in meters.""" + z_range: tuple[float, float] = (-1e6, 1e6) + """Allowed range of z coordinates (world height) for sampled patches, in meters.""" + grid_resolution: float | None = None + """Resolution of the grid used for flat-patch detection, in meters. When + ``None`` (default), the terrain's own ``horizontal_scale`` is used. Set to a + smaller value (e.g. 0.025) for finer boundary precision at the cost of a + larger intermediate grid.""" + + +@dataclass +class TerrainGeometry: + geom: mujoco.MjsGeom | None = None + """MuJoCo geometry spec element, or None.""" + hfield: mujoco.MjsHField | None = None + """MuJoCo heightfield spec element, or None.""" + color: tuple[float, float, float, float] | None = None + """RGBA color override for this geometry, or None to use default.""" + + +@dataclass +class TerrainOutput: + origin: np.ndarray + """Spawn origin position (x, y, z) in the sub-terrain's local frame.""" + geometries: list[TerrainGeometry] + """List of geometry elements comprising this terrain.""" + flat_patches: dict[str, np.ndarray] | None = None + """Named sets of flat patch positions, each an (N, 3) array. None if not configured.""" + + +@dataclass +class SubTerrainCfg(abc.ABC): + proportion: float = 1.0 + """Terrain type allocation weight (behavior depends on curriculum mode): + + - curriculum=True: Controls column allocation. Normalized proportions determine + how many columns each terrain type occupies via cumulative distribution. + Example: proportions [0.5, 0.5] with num_cols=2 gives one terrain per column. + + - curriculum=False: Sampling probability for each patch. Each patch independently + samples a terrain type weighted by normalized proportions. + """ + size: tuple[float, float] = (10.0, 10.0) + """Width and length of the terrain patch, in meters.""" + flat_patch_sampling: dict[str, FlatPatchSamplingCfg] | None = None + """Named flat-patch sampling configurations, or None to disable.""" + + @abc.abstractmethod + def function( + self, difficulty: float, spec: mujoco.MjSpec, rng: np.random.Generator + ) -> TerrainOutput: + """Generate terrain geometry. + + Returns: + TerrainOutput containing spawn origin and list of geometries. + """ + raise NotImplementedError + + +@dataclass(kw_only=True) +class TerrainGeneratorCfg: + seed: int | None = None + """Random seed for terrain generation. None uses a random seed.""" + curriculum: bool = False + """Controls terrain allocation mode: + + - curriculum=True: Each column gets ONE terrain type (deterministic allocation). + Difficulty increases along rows. Use this to ensure each terrain type occupies + its own column(s). + + - curriculum=False: Every patch is randomly sampled from all terrain types. + Proportions control sampling probability. Use this for random variety. + + Example: With 2 terrain types and num_cols=2, curriculum=True gives one terrain + per column. curriculum=False gives a random mix of both types in all patches. + """ + size: tuple[float, float] + """Width and length of each sub-terrain patch, in meters.""" + border_width: float = 0.0 + """Width of the flat border around the entire terrain grid, in meters.""" + border_height: float = 1.0 + """Height of the border wall around the terrain grid, in meters.""" + num_rows: int = 1 + """Number of sub-terrain rows in the grid. Represents difficulty levels in + curriculum mode. Note: Environments are randomly assigned to rows, so multiple + envs can share the same patch.""" + num_cols: int = 1 + """Number of sub-terrain columns in the grid. Represents terrain type variants. + Note: Environments are evenly distributed across columns (not random).""" + color_scheme: Literal["height", "random", "none"] = "height" + """Coloring strategy for terrain geometry. "height" colors by elevation, + "random" assigns random colors, "none" uses uniform gray.""" + sub_terrains: dict[str, SubTerrainCfg] = field(default_factory=dict) + """Named sub-terrain configurations to populate the grid.""" + difficulty_range: tuple[float, float] = (0.0, 1.0) + """Min and max difficulty values used when generating sub-terrains.""" + add_lights: bool = False + """If True, adds a directional light above the terrain grid.""" + + +class TerrainGenerator: + """Generates procedural terrain grids with configurable difficulty. + + Creates a grid of terrain patches where each patch can be a different + terrain type. Supports two modes: + + - **Random mode** (curriculum=False): Every patch independently samples a + terrain type weighted by proportions. Results in random variety across + all patches. + + - **Curriculum mode** (curriculum=True): Columns are deterministically + assigned to terrain types based on proportions. All patches in a column + share the same terrain type, with difficulty increasing along rows. + Use this to ensure each terrain type occupies specific column(s). + + Terrain types are weighted by proportion and their geometry is generated + based on a difficulty value in the configured range. The grid is centered + at the world origin. A border can be added around the entire grid along with + optional overhead lighting. + """ + + def __init__(self, cfg: TerrainGeneratorCfg, device: str = "cpu") -> None: + if len(cfg.sub_terrains) == 0: + raise ValueError("At least one sub_terrain must be specified.") + + self.cfg = cfg + self.device = device + + for sub_cfg in self.cfg.sub_terrains.values(): + sub_cfg.size = self.cfg.size + + if self.cfg.seed is not None: + seed = self.cfg.seed + else: + seed = np.random.randint(0, 10000) + self.np_rng = np.random.default_rng(seed) + + self.terrain_origins = np.zeros((self.cfg.num_rows, self.cfg.num_cols, 3)) + + # Pre-allocate flat patch storage by scanning all sub-terrain configs. + self.flat_patches: dict[str, np.ndarray] = {} + self.flat_patch_radii: dict[str, float] = {} + patch_names: dict[str, int] = {} + for sub_cfg in self.cfg.sub_terrains.values(): + if sub_cfg.flat_patch_sampling is not None: + for name, patch_cfg in sub_cfg.flat_patch_sampling.items(): + if name in patch_names: + patch_names[name] = max(patch_names[name], patch_cfg.num_patches) + else: + patch_names[name] = patch_cfg.num_patches + self.flat_patch_radii[name] = max( + self.flat_patch_radii.get(name, 0.0), patch_cfg.patch_radius + ) + for name, max_num_patches in patch_names.items(): + self.flat_patches[name] = np.zeros( + (self.cfg.num_rows, self.cfg.num_cols, max_num_patches, 3) + ) + + def compile(self, spec: mujoco.MjSpec) -> None: + body = spec.worldbody.add_body(name="terrain") + + if self.cfg.curriculum: + tic = time.perf_counter() + self._generate_curriculum_terrains(spec) + toc = time.perf_counter() + print(f"Curriculum terrain generation took {toc - tic:.4f} seconds.") + + else: + tic = time.perf_counter() + self._generate_random_terrains(spec) + toc = time.perf_counter() + print(f"Terrain generation took {toc - tic:.4f} seconds.") + + self._add_terrain_border(spec) + self._add_grid_lights(spec) + + counter = 0 + for geom in body.geoms: + geom.name = f"terrain_{counter}" + counter += 1 + + def _generate_random_terrains(self, spec: mujoco.MjSpec) -> None: + # Normalize the proportions of the sub-terrains. + proportions = np.array( + [sub_cfg.proportion for sub_cfg in self.cfg.sub_terrains.values()] + ) + proportions /= np.sum(proportions) + + sub_terrains_cfgs = list(self.cfg.sub_terrains.values()) + + # Randomly sample and place sub-terrains in the grid. + for index in range(self.cfg.num_rows * self.cfg.num_cols): + sub_row, sub_col = np.unravel_index(index, (self.cfg.num_rows, self.cfg.num_cols)) + sub_row = int(sub_row) + sub_col = int(sub_col) + + # Randomly select a sub-terrain type and difficulty. + sub_index = self.np_rng.choice(len(proportions), p=proportions) + difficulty = self.np_rng.uniform(*self.cfg.difficulty_range) + + # Calculate the world position for this sub-terrain. + world_position = self._get_sub_terrain_position(sub_row, sub_col) + + # Create the terrain mesh and get the spawn origin in world coordinates. + spawn_origin = self._create_terrain_geom( + spec, + world_position, + difficulty, + sub_terrains_cfgs[sub_index], + sub_row, + sub_col, + ) + + # Store the spawn origin for this terrain. + self.terrain_origins[sub_row, sub_col] = spawn_origin + + def _generate_curriculum_terrains(self, spec: mujoco.MjSpec) -> None: + # Normalize the proportions of the sub-terrains. + proportions = np.array( + [sub_cfg.proportion for sub_cfg in self.cfg.sub_terrains.values()] + ) + proportions /= np.sum(proportions) + + sub_indices = [] + for index in range(self.cfg.num_cols): + sub_index = np.min( + np.where(index / self.cfg.num_cols + 0.001 < np.cumsum(proportions))[0] + ) + sub_indices.append(sub_index) + sub_indices = np.array(sub_indices, dtype=np.int32) + + sub_terrains_cfgs = list(self.cfg.sub_terrains.values()) + + for sub_col in range(self.cfg.num_cols): + for sub_row in range(self.cfg.num_rows): + lower, upper = self.cfg.difficulty_range + difficulty = (sub_row + self.np_rng.uniform()) / self.cfg.num_rows + difficulty = lower + (upper - lower) * difficulty + world_position = self._get_sub_terrain_position(sub_row, sub_col) + spawn_origin = self._create_terrain_geom( + spec, + world_position, + difficulty, + sub_terrains_cfgs[sub_indices[sub_col]], + sub_row, + sub_col, + ) + self.terrain_origins[sub_row, sub_col] = spawn_origin + + def _get_sub_terrain_position(self, row: int, col: int) -> np.ndarray: + """Get the world position for a sub-terrain at the given grid indices. + + This returns the position of the sub-terrain's corner (not center). + The entire grid is centered at the world origin. + """ + # Calculate position relative to grid corner. + rel_x = row * self.cfg.size[0] + rel_y = col * self.cfg.size[1] + + # Offset to center the entire grid at world origin. + grid_offset_x = -self.cfg.num_rows * self.cfg.size[0] * 0.5 + grid_offset_y = -self.cfg.num_cols * self.cfg.size[1] * 0.5 + + return np.array([grid_offset_x + rel_x, grid_offset_y + rel_y, 0.0]) + + def _create_terrain_geom( + self, + spec: mujoco.MjSpec, + world_position: np.ndarray, + difficulty: float, + cfg: SubTerrainCfg, + sub_row: int, + sub_col: int, + ) -> np.ndarray: + """Create a terrain geometry at the specified world position. + + Args: + spec: MuJoCo spec to add geometry to. + world_position: World position of the terrain's corner. + difficulty: Difficulty parameter for terrain generation. + cfg: Sub-terrain configuration. + sub_row: Row index in the terrain grid. + sub_col: Column index in the terrain grid. + + Returns: + The spawn origin in world coordinates. + """ + output = cfg.function(difficulty, spec, self.np_rng) + for terrain_geom in output.geometries: + if terrain_geom.geom is not None: + terrain_geom.geom.pos = np.array(terrain_geom.geom.pos) + world_position + if terrain_geom.geom.material is not None: + if self.cfg.color_scheme == "height" and terrain_geom.color: + terrain_geom.geom.rgba[:] = terrain_geom.color + elif self.cfg.color_scheme == "random": + terrain_geom.geom.rgba[:3] = self.np_rng.uniform(0.3, 0.8, 3) + terrain_geom.geom.rgba[3] = 1.0 + elif self.cfg.color_scheme == "none": + terrain_geom.geom.rgba[:] = (0.5, 0.5, 0.5, 1.0) + + # Collect flat patches into pre-allocated arrays. + spawn_origin = output.origin + world_position + for name, arr in self.flat_patches.items(): + if output.flat_patches is not None and name in output.flat_patches: + patches = output.flat_patches[name] + arr[sub_row, sub_col, : len(patches)] = patches + world_position + arr[sub_row, sub_col, len(patches) :] = spawn_origin + else: + # Sub-terrain didn't produce patches: fill with spawn origin so that + # every slot contains a valid position for reset_root_state_from_flat_patches. + arr[sub_row, sub_col] = spawn_origin + + return spawn_origin + + def _add_terrain_border(self, spec: mujoco.MjSpec) -> None: + if self.cfg.border_width <= 0.0: + return + body = spec.body("terrain") + border_size = ( + self.cfg.num_rows * self.cfg.size[0] + 2 * self.cfg.border_width, + self.cfg.num_cols * self.cfg.size[1] + 2 * self.cfg.border_width, + ) + inner_size = ( + self.cfg.num_rows * self.cfg.size[0], + self.cfg.num_cols * self.cfg.size[1], + ) + # Border should be centered at origin since the terrain grid is centered. + border_center = (0, 0, -self.cfg.border_height / 2) + boxes = make_border( + body, + border_size, + inner_size, + height=abs(self.cfg.border_height), + position=border_center, + ) + for box in boxes: + if self.cfg.color_scheme == "random": + box.rgba = RGBA.random(self.np_rng, alpha=1.0) + else: + box.rgba = _DARK_GRAY + + def _add_grid_lights(self, spec: mujoco.MjSpec) -> None: + if not self.cfg.add_lights: + return + + total_width = self.cfg.size[0] * self.cfg.num_rows + total_height = self.cfg.size[1] * self.cfg.num_cols + light_height = max(total_width, total_height) * 0.6 + + spec.body("terrain").add_light( + pos=(0, 0, light_height), + type=mujoco.mjtLightType.mjLIGHT_DIRECTIONAL, + dir=(0, 0, -1), + ) diff --git a/mjlab/src/mjlab/terrains/terrain_importer.py b/mjlab/src/mjlab/terrains/terrain_importer.py new file mode 100644 index 0000000000000000000000000000000000000000..6a1575ef30240e91d29a6888915bff7a206d9d2e --- /dev/null +++ b/mjlab/src/mjlab/terrains/terrain_importer.py @@ -0,0 +1,333 @@ +from __future__ import annotations + +from dataclasses import dataclass +from typing import Literal + +import mujoco +import numpy as np +import torch + +from mjlab.terrains.terrain_generator import TerrainGenerator, TerrainGeneratorCfg +from mjlab.utils import spec_config as spec_cfg + +_DEFAULT_PLANE_TEXTURE = spec_cfg.TextureCfg( + name="groundplane", + type="2d", + builtin="checker", + mark="edge", + rgb1=(0.2, 0.3, 0.4), + rgb2=(0.1, 0.2, 0.3), + markrgb=(0.8, 0.8, 0.8), + width=300, + height=300, +) + +_DEFAULT_PLANE_MATERIAL = spec_cfg.MaterialCfg( + name="groundplane", + texuniform=True, + texrepeat=(4, 4), + reflectance=0.2, + texture="groundplane", +) + + +@dataclass +class TerrainImporterCfg: + """Configuration for terrain import and environment placement.""" + + terrain_type: Literal["generator", "plane"] = "plane" + """Type of terrain to generate. "generator" uses procedural terrain with + sub-terrain grid, "plane" creates a flat ground plane.""" + terrain_generator: TerrainGeneratorCfg | None = None + """Configuration for procedural terrain generation. Required when + terrain_type is "generator".""" + env_spacing: float | None = 2.0 + """Distance between environment origins when using grid layout. Required for + "plane" terrain or when no sub-terrain origins exist.""" + max_init_terrain_level: int | None = None + """Maximum initial difficulty level (row index) for environment placement in + curriculum mode. None uses all available rows.""" + num_envs: int = 1 + """Number of parallel environments to create. This will get overridden by the + scene configuration if specified there.""" + + +class TerrainImporter: + """Builds a MuJoCo spec with terrain geometry and maps environments to spawn origins. + + The terrain is a grid of sub-terrain patches (num_rows x num_cols), each with + a spawn origin. When num_envs exceeds the number of patches, environment + origins are sampled from the sub-terrain origins. + + .. note:: + Environment allocation for procedural terrain: Columns (terrain types) are + evenly distributed across environments, but rows (difficulty levels) are + randomly sampled. This means multiple environments can spawn on the same + (row, col) patch, leaving others unoccupied, even when num_envs > num_patches. + + See FAQ: "How does env_origins determine robot layout?" + """ + + def __init__(self, cfg: TerrainImporterCfg, device: str) -> None: + self.cfg = cfg + self.device = device + self._spec = mujoco.MjSpec() + + # The origins of the environments. Shape is (num_envs, 3). + self.env_origins = None + + # Origins of the sub-terrains. Shape is (num_rows, num_cols, 3). + # If terrain origins is not None, the environment origins are computed based on the + # terrain origins. Otherwise, the origins are computed based on grid spacing. + self.terrain_origins = None + + if self.cfg.terrain_type == "generator": + if self.cfg.terrain_generator is None: + raise ValueError( + "terrain_generator must be specified for terrain_type 'generator'" + ) + terrain_generator = TerrainGenerator(self.cfg.terrain_generator, device=device) + terrain_generator.compile(self._spec) + self.configure_env_origins(terrain_generator.terrain_origins) + self._flat_patches: dict[str, torch.Tensor] = { + name: torch.from_numpy(arr).to(device=device, dtype=torch.float) + for name, arr in terrain_generator.flat_patches.items() + } + self._flat_patch_radii: dict[str, float] = dict( + terrain_generator.flat_patch_radii + ) + elif self.cfg.terrain_type == "plane": + self.import_ground_plane("terrain") + self.configure_env_origins() + self._flat_patches: dict[str, torch.Tensor] = {} + self._flat_patch_radii: dict[str, float] = {} + else: + raise ValueError(f"Unknown terrain type: {self.cfg.terrain_type}") + + self._add_env_origin_sites() + self._add_terrain_origin_sites() + self._add_flat_patch_sites() + + def _add_env_origin_sites(self) -> None: + """Add transparent sphere sites at each environment origin for visualization.""" + if self.env_origins is None: + return + + origin_site_radius: float = 0.3 + origin_site_color: tuple[float, float, float, float] = (0.2, 0.6, 0.2, 0.3) + + # Convert torch tensor to numpy if needed + if isinstance(self.env_origins, torch.Tensor): + env_origins_np = self.env_origins.cpu().numpy() + else: + env_origins_np = self.env_origins + + for env_id, origin in enumerate(env_origins_np): + self._spec.worldbody.add_site( + name=f"env_origin_{env_id}", + pos=origin, + size=(origin_site_radius,) * 3, + type=mujoco.mjtGeom.mjGEOM_SPHERE, + rgba=origin_site_color, + group=4, + ) + + def _add_terrain_origin_sites(self) -> None: + """Add transparent sphere sites at each terrain origin for visualization.""" + if self.terrain_origins is None: + return + + # Convert torch tensor to numpy if needed + if isinstance(self.terrain_origins, torch.Tensor): + terrain_origins_np = self.terrain_origins.cpu().numpy() + else: + terrain_origins_np = self.terrain_origins + + terrain_origin_site_radius: float = 0.5 + terrain_origin_site_color: tuple[float, float, float, float] = (0.2, 0.2, 0.6, 0.3) + + # Iterate through the 2D grid of terrain origins + num_rows, num_cols = terrain_origins_np.shape[:2] + for row in range(num_rows): + for col in range(num_cols): + origin = terrain_origins_np[row, col] + self._spec.worldbody.add_site( + name=f"terrain_origin_{row}_{col}", + pos=origin, + size=(terrain_origin_site_radius,) * 3, + type=mujoco.mjtGeom.mjGEOM_SPHERE, + rgba=terrain_origin_site_color, + group=5, + ) + + def _add_flat_patch_sites(self) -> None: + """Add transparent box sites at each flat patch location for visualization.""" + if not self._flat_patches: + return + site_thickness = 0.02 + site_color = (0.9, 0.6, 0.1, 0.1) + for name, patches_tensor in self._flat_patches.items(): + radius = self._flat_patch_radii.get(name, 0.5) + patches_np = patches_tensor.cpu().numpy() + num_rows, num_cols, num_patches, _ = patches_np.shape + for row in range(num_rows): + for col in range(num_cols): + for p in range(num_patches): + pos = patches_np[row, col, p] + self._spec.worldbody.add_site( + name=f"flat_patch_{name}_{row}_{col}_{p}", + pos=pos, + size=(radius, radius, site_thickness), + type=mujoco.mjtGeom.mjGEOM_BOX, + rgba=site_color, + group=3, + ) + + @property + def spec(self) -> mujoco.MjSpec: + return self._spec + + @property + def flat_patches(self) -> dict[str, torch.Tensor]: + return self._flat_patches + + def import_ground_plane(self, name: str) -> None: + _DEFAULT_PLANE_TEXTURE.edit_spec(self._spec) + _DEFAULT_PLANE_MATERIAL.edit_spec(self._spec) + self._spec.worldbody.add_body(name=name).add_geom( + name=name, + type=mujoco.mjtGeom.mjGEOM_PLANE, + size=(0, 0, 0.01), + material=_DEFAULT_PLANE_MATERIAL.name, + ) + spec_cfg.LightCfg(pos=(0, 0, 1.5), type="directional").edit_spec(self._spec) + + def configure_env_origins(self, origins: np.ndarray | torch.Tensor | None = None): + """Configure the origins of the environments based on the added terrain.""" + if origins is not None: + if isinstance(origins, np.ndarray): + origins = torch.from_numpy(origins) + else: + assert isinstance(origins, torch.Tensor) + self.terrain_origins = origins.to(self.device, dtype=torch.float) + self.env_origins = self._compute_env_origins_curriculum( + self.cfg.num_envs, self.terrain_origins + ) + else: + self.terrain_origins = None + if self.cfg.env_spacing is None: + raise ValueError( + "Environment spacing must be specified for configuring grid-like origins." + ) + self.env_origins = self._compute_env_origins_grid( + self.cfg.num_envs, self.cfg.env_spacing + ) + + def update_env_origins( + self, env_ids: torch.Tensor, move_up: torch.Tensor, move_down: torch.Tensor + ): + """Update the environment origins based on the terrain levels.""" + if self.terrain_origins is None: + return + assert self.env_origins is not None + self.terrain_levels[env_ids] += 1 * move_up - 1 * move_down + self.terrain_levels[env_ids] = torch.where( + self.terrain_levels[env_ids] >= self.max_terrain_level, + torch.randint_like(self.terrain_levels[env_ids], self.max_terrain_level), + torch.clip(self.terrain_levels[env_ids], 0), + ) + self.env_origins[env_ids] = self.terrain_origins[ + self.terrain_levels[env_ids], self.terrain_types[env_ids] + ] + + def randomize_env_origins(self, env_ids: torch.Tensor) -> None: + """Randomize the environment origins to random sub-terrains. + + This randomizes both the terrain level (row) and terrain type (column), + useful for play/evaluation mode where you want to test on varied terrains. + """ + if self.terrain_origins is None: + return + assert self.env_origins is not None + num_rows, num_cols = self.terrain_origins.shape[:2] + num_envs = len(env_ids) + self.terrain_levels[env_ids] = torch.randint( + 0, num_rows, (num_envs,), device=self.device + ) + self.terrain_types[env_ids] = torch.randint( + 0, num_cols, (num_envs,), device=self.device + ) + self.env_origins[env_ids] = self.terrain_origins[ + self.terrain_levels[env_ids], self.terrain_types[env_ids] + ] + + def _compute_env_origins_curriculum( + self, num_envs: int, origins: torch.Tensor + ) -> torch.Tensor: + """Compute the origins of the environments defined by the sub-terrains origins. + + Allocation strategy: + - Columns (terrain_types): Evenly distributed across environments using + integer division. Each column gets floor(num_envs / num_cols) or + ceil(num_envs / num_cols) envs. + - Rows (terrain_levels): Randomly sampled from [0, max_init_terrain_level]. + Supports curriculum learning where rows represent difficulty levels. + + .. note:: + Multiple environments can be assigned to the same (row, col) patch, leaving + other patches unoccupied, even when num_envs > num_patches. This is because + row assignment is random while column assignment is deterministic. + + Example: 5x5 terrain grid (25 patches), 100 environments: + - Each of 5 columns gets exactly 20 environments + - Those 20 are randomly distributed across 5 rows + - Result: Some patches get 0 envs, others might get 5+ + + See FAQ: "How does env_origins determine robot layout?" + """ + num_rows, num_cols = origins.shape[:2] + if self.cfg.max_init_terrain_level is None: + max_init_level = num_rows - 1 + else: + max_init_level = min(self.cfg.max_init_terrain_level, num_rows - 1) + self.max_terrain_level = num_rows + self.terrain_levels = torch.randint( + 0, max_init_level + 1, (num_envs,), device=self.device + ) + self.terrain_types = torch.div( + torch.arange(num_envs, device=self.device), + (num_envs / num_cols), + rounding_mode="floor", + ).to(torch.long) + env_origins = torch.zeros(num_envs, 3, device=self.device) + env_origins[:] = origins[self.terrain_levels, self.terrain_types] + return env_origins + + def _compute_env_origins_grid( + self, num_envs: int, env_spacing: float + ) -> torch.Tensor: + """Compute the origins of the environments in a grid based on configured spacing. + + Creates an approximately square grid centered at the world origin where: + - num_rows ≈ ceil(sqrt(num_envs)) + - num_cols = ceil(num_envs / num_rows) + + Examples: + - 32 envs → 7 rows x 5 cols + - 64 envs → 8 rows x 8 cols + - 4096 envs → 64 rows x 64 cols + + See FAQ: "How does env_origins determine robot layout?" + """ + env_origins = torch.zeros(num_envs, 3, device=self.device) + num_rows = np.ceil(num_envs / int(np.sqrt(num_envs))) + num_cols = np.ceil(num_envs / num_rows) + ii, jj = torch.meshgrid( + torch.arange(num_rows, device=self.device), + torch.arange(num_cols, device=self.device), + indexing="ij", + ) + env_origins[:, 0] = -(ii.flatten()[:num_envs] - (num_rows - 1) / 2) * env_spacing + env_origins[:, 1] = (jj.flatten()[:num_envs] - (num_cols - 1) / 2) * env_spacing + env_origins[:, 2] = 0.0 + return env_origins diff --git a/mjlab/src/mjlab/terrains/utils.py b/mjlab/src/mjlab/terrains/utils.py new file mode 100644 index 0000000000000000000000000000000000000000..ff48515fde73e54a385efb724114e221dbd91a1f --- /dev/null +++ b/mjlab/src/mjlab/terrains/utils.py @@ -0,0 +1,210 @@ +"""Utility functions for terrain generation. + +References: + IsaacLab terrain utilities: + https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab/isaaclab/terrains/trimesh/utils.py +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING + +import mujoco +import numpy as np +from scipy import ndimage + +if TYPE_CHECKING: + from mjlab.terrains.terrain_generator import FlatPatchSamplingCfg + + +def find_flat_patches_from_heightfield( + heights: np.ndarray, + horizontal_scale: float, + z_offset: float, + cfg: FlatPatchSamplingCfg, + rng: np.random.Generator, +) -> np.ndarray: + """Find flat patches on a heightfield surface using morphological filtering. + + Slides a circular footprint over every pixel and keeps those where the + height variation is within tolerance. Randomly samples from the valid set. + + Args: + heights: 2D array of physical heights (meters), shape (num_rows, num_cols). + horizontal_scale: Physical size of each pixel in meters. + z_offset: Vertical offset of the heightfield origin. + cfg: Flat patch sampling configuration. + rng: Random number generator. + + Returns: + Array of shape (num_patches, 3) with (x, y, z) positions in sub-terrain + local frame. + """ + # Optionally upsample to a finer grid for higher-precision boundary detection. + if cfg.grid_resolution is not None and cfg.grid_resolution < horizontal_scale: + zoom_factor = horizontal_scale / cfg.grid_resolution + heights = np.asarray(ndimage.zoom(heights, zoom_factor, order=1)) + horizontal_scale = cfg.grid_resolution + + num_rows, num_cols = heights.shape + + # Build circular footprint. + radius_pixels = int(np.ceil(cfg.patch_radius / horizontal_scale)) + y_grid, x_grid = np.ogrid[ + -radius_pixels : radius_pixels + 1, -radius_pixels : radius_pixels + 1 + ] + footprint = (x_grid**2 + y_grid**2) <= radius_pixels**2 + + # Morphological max/min filter to find height variation within footprint. + # Use constant padding so edge pixels where the footprint extends outside + # the data are not incorrectly marked flat (default 'reflect' hides edges). + max_h = ndimage.maximum_filter( + heights, footprint=footprint, mode="constant", cval=-np.inf + ) + min_h = ndimage.minimum_filter( + heights, footprint=footprint, mode="constant", cval=np.inf + ) + valid_mask = (max_h - min_h) <= cfg.max_height_diff + + # Exclude pixels whose footprint would extend outside the array. This + # ensures the full patch circle lies within the heightfield bounds. + valid_mask[:radius_pixels, :] = False + valid_mask[-radius_pixels:, :] = False + valid_mask[:, :radius_pixels] = False + valid_mask[:, -radius_pixels:] = False + + # Apply spatial range constraints. + # MuJoCo hfield convention: columns map to the x-axis, rows map to the + # y-axis (see engine_ray.c vertex: {dx*c - size[0], dy*r - size[1], ...}). + x_coords = np.arange(num_cols) * horizontal_scale + y_coords = np.arange(num_rows) * horizontal_scale + + x_valid = (x_coords >= cfg.x_range[0]) & (x_coords <= cfg.x_range[1]) + y_valid = (y_coords >= cfg.y_range[0]) & (y_coords <= cfg.y_range[1]) + valid_mask &= y_valid[:, None] & x_valid[None, :] + + # Apply z range constraint. + z_values = heights + z_offset + z_valid = (z_values >= cfg.z_range[0]) & (z_values <= cfg.z_range[1]) + valid_mask &= z_valid + + valid_indices = np.argwhere(valid_mask) + + if len(valid_indices) == 0: + # Fallback: return sub-terrain center repeated. + center_x = num_cols * horizontal_scale / 2.0 + center_y = num_rows * horizontal_scale / 2.0 + center_row = min(num_rows // 2, num_rows - 1) + center_col = min(num_cols // 2, num_cols - 1) + center_z = heights[center_row, center_col] + z_offset + return np.tile([center_x, center_y, center_z], (cfg.num_patches, 1)) + + replace = len(valid_indices) < cfg.num_patches + chosen = rng.choice(len(valid_indices), size=cfg.num_patches, replace=replace) + selected = valid_indices[chosen] + + x = selected[:, 1] * horizontal_scale + y = selected[:, 0] * horizontal_scale + z = heights[selected[:, 0], selected[:, 1]] + z_offset + + return np.stack([x, y, z], axis=-1) + + +def make_plane( + body: mujoco.MjsBody, + size: tuple[float, float], + height: float, + center_zero: bool = True, + plane_thickness: float = 1.0, +): + """Create finite plane using box geometry. + + Uses box instead of MuJoCo plane to avoid infinite extent in terrain grids. + Thickness prevents penetration issues. + """ + if center_zero: + pos = (0, 0, height - plane_thickness / 2.0) + else: + pos = (size[0] / 2.0, size[1] / 2.0, height - plane_thickness / 2.0) + + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(size[0] / 2.0, size[1] / 2.0, plane_thickness / 2.0), + pos=pos, + ) + return [box] + + +def make_border( + body: mujoco.MjsBody, + size: tuple[float, float], + inner_size: tuple[float, float], + height: float, + position: tuple[float, float, float], +): + """Create rectangular border using four box geometries. + + Returns top, bottom, left, right boxes forming a hollow rectangle. + """ + boxes = [] + + thickness_x = (size[0] - inner_size[0]) / 2.0 + thickness_y = (size[1] - inner_size[1]) / 2.0 + + box_dims = (size[0], thickness_y, height) + + # Top. + box_pos = ( + position[0], + position[1] + inner_size[1] / 2.0 + thickness_y / 2.0, + position[2], + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(box_dims[0] / 2.0, box_dims[1] / 2.0, box_dims[2] / 2.0), + pos=box_pos, + ) + boxes.append(box) + + # Bottom. + box_pos = ( + position[0], + position[1] - inner_size[1] / 2.0 - thickness_y / 2.0, + position[2], + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(box_dims[0] / 2.0, box_dims[1] / 2.0, box_dims[2] / 2.0), + pos=box_pos, + ) + boxes.append(box) + + box_dims = (thickness_x, inner_size[1], height) + + # Left. + box_pos = ( + position[0] - inner_size[0] / 2.0 - thickness_x / 2.0, + position[1], + position[2], + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(box_dims[0] / 2.0, box_dims[1] / 2.0, box_dims[2] / 2.0), + pos=box_pos, + ) + boxes.append(box) + + # Right. + box_pos = ( + position[0] + inner_size[0] / 2.0 + thickness_x / 2.0, + position[1], + position[2], + ) + box = body.add_geom( + type=mujoco.mjtGeom.mjGEOM_BOX, + size=(box_dims[0] / 2.0, box_dims[1] / 2.0, box_dims[2] / 2.0), + pos=box_pos, + ) + boxes.append(box) + + return boxes diff --git a/mjlab/src/mjlab/utils/__init__.py b/mjlab/src/mjlab/utils/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391 diff --git a/mjlab/src/mjlab/utils/actuator.py b/mjlab/src/mjlab/utils/actuator.py new file mode 100644 index 0000000000000000000000000000000000000000..465170abc5b2f1b89086390852ec060d9c661a9d --- /dev/null +++ b/mjlab/src/mjlab/utils/actuator.py @@ -0,0 +1,80 @@ +"""Electric actuator utilities.""" + +import math +from dataclasses import dataclass +from typing import NamedTuple + + +@dataclass(frozen=True) +class ElectricActuator: + """Electric actuator parameters.""" + + reflected_inertia: float + velocity_limit: float + effort_limit: float + + +def reflected_inertia( + rotor_inertia: float, + gear_ratio: float, +) -> float: + """Compute reflected inertia of a single-stage gearbox.""" + return rotor_inertia * gear_ratio**2 + + +def reflected_inertia_from_two_stage_planetary( + rotor_inertia: tuple[float, float, float], + gear_ratio: tuple[float, float, float], +) -> float: + """Compute reflected inertia of a two-stage planetary gearbox.""" + assert gear_ratio[0] == 1 + r1 = rotor_inertia[0] * (gear_ratio[1] * gear_ratio[2]) ** 2 + r2 = rotor_inertia[1] * gear_ratio[2] ** 2 + r3 = rotor_inertia[2] + return r1 + r2 + r3 + + +def rpm_to_rad(rpm: float) -> float: + """Convert revolutions per minute to radians per second.""" + return (rpm * 2 * math.pi) / 60 + + +class LinearJointProperties(NamedTuple): + """Linear joint properties reflected from a rotary actuator.""" + + armature: float # kg + velocity_limit: float # m/s + effort_limit: float # N + + +def reflect_rotary_to_linear( + armature_rotary: float, + velocity_limit_rotary: float, + effort_limit_rotary: float, + transmission_ratio: float, +) -> LinearJointProperties: + """Reflect rotary motor properties through a transmission to linear joint properties. + + Converts motor specs from rotary coordinates (rad, rad/s, Nm) to equivalent linear + properties (kg, m/s, N) for simulation. Uses energy and power equivalence: + - Linear mass: m = I / r² + - Linear velocity: v = r · ω + - Linear force: F = τ / r + where r is the transmission ratio [m/rad]. + + Args: + armature_rotary: Reflected inertia at motor output [kg⋅m²]. + velocity_limit_rotary: Maximum angular velocity [rad/s]. + effort_limit_rotary: Maximum torque [Nm]. + transmission_ratio: Linear displacement per radian [m/rad]. + + Returns: + Linear joint properties (armature [kg], velocity_limit [m/s], effort_limit [N]) + """ + armature_linear = armature_rotary / (transmission_ratio**2) + velocity_limit_linear = velocity_limit_rotary * transmission_ratio + effort_limit_linear = effort_limit_rotary / transmission_ratio + + return LinearJointProperties( + armature_linear, velocity_limit_linear, effort_limit_linear + ) diff --git a/mjlab/src/mjlab/utils/color.py b/mjlab/src/mjlab/utils/color.py new file mode 100644 index 0000000000000000000000000000000000000000..ee69a2ef06543a6e4010782c065f34c3378511d7 --- /dev/null +++ b/mjlab/src/mjlab/utils/color.py @@ -0,0 +1,223 @@ +"""Color manipulation utilities for RGB/HSV conversions and transformations.""" + +from typing import NamedTuple, Tuple + +import numpy as np + + +class RGB(NamedTuple): + """RGB color with values in range [0, 1].""" + + r: float + g: float + b: float + + def to_tuple(self) -> Tuple[float, float, float]: + """Convert to tuple representation.""" + return (self.r, self.g, self.b) + + @staticmethod + def random(rng: np.random.Generator) -> "RGB": + """Generate a random RGB color.""" + return RGB(rng.random(), rng.random(), rng.random()) + + +class RGBA(NamedTuple): + """RGBA color with values in range [0, 1].""" + + r: float + g: float + b: float + a: float + + @classmethod + def from_rgb(cls, rgb: RGB, alpha: float = 1.0) -> "RGBA": + """Create RGBA from RGB with specified alpha.""" + return cls(rgb.r, rgb.g, rgb.b, alpha) + + @staticmethod + def random(rng: np.random.Generator, alpha: float = 1.0) -> "RGBA": + """Generate a random RGBA color with specified alpha.""" + rgb = RGB.random(rng) + return RGBA(rgb.r, rgb.g, rgb.b, alpha) + + +class HSV(NamedTuple): + """HSV color representation.""" + + h: float # Hue in range [0, 1]. + s: float # Saturation in range [0, 1]. + v: float # Value in range [0, 1]. + + +def rgb_to_hsv(rgb: Tuple[float, float, float]) -> HSV: + """Convert RGB to HSV color space. + + Args: + rgb: RGB color tuple with values in range [0, 1]. + + Returns: + HSV color representation. + """ + r, g, b = rgb + max_val = max(r, g, b) + min_val = min(r, g, b) + delta = max_val - min_val + + # Calculate Value. + v = max_val + + # Calculate Saturation. + s = 0.0 if max_val == 0 else delta / max_val + + # Calculate Hue. + if delta == 0: + h = 0.0 + elif max_val == r: + h = ((g - b) / delta) % 6 + elif max_val == g: + h = (b - r) / delta + 2 + else: + h = (r - g) / delta + 4 + + h /= 6.0 # Normalize to [0, 1]. + + return HSV(h, s, v) + + +def hsv_to_rgb(hsv: HSV) -> Tuple[float, float, float]: + """Convert HSV to RGB color space. + + Args: + hsv: HSV color representation. + + Returns: + RGB color tuple with values in range [0, 1]. + """ + h, s, v = hsv.h, hsv.s, hsv.v + + i = int(h * 6) + f = h * 6 - i + p = v * (1 - s) + q = v * (1 - f * s) + t = v * (1 - (1 - f) * s) + + i %= 6 + + if i == 0: + return (v, t, p) + elif i == 1: + return (q, v, p) + elif i == 2: + return (p, v, t) + elif i == 3: + return (p, q, v) + elif i == 4: + return (t, p, v) + else: + return (v, p, q) + + +def clamp(value: float, min_val: float = 0.0, max_val: float = 1.0) -> float: + """Clamp a value between min and max.""" + return max(min_val, min(value, max_val)) + + +def brand_ramp( + base_rgb: Tuple[float, float, float], t: float, alpha: float = 1.0 +) -> Tuple[float, float, float, float]: + """Create a color ramp from a base RGB color using parameter t. + + This function creates a color variation by adjusting saturation and + value based on the parameter t, useful for creating color gradients + or variations of a brand color. + + Args: + base_rgb: Base RGB color tuple with values in range [0, 1]. + t: Ramp parameter in range [0, 1], where 0 is darkest and 1 is brightest. + alpha: Alpha transparency value in range [0, 1]. + + Returns: + RGBA color tuple representing the ramped color. + + Raises: + ValueError: If t is not in range [0, 1]. + """ + if not 0 <= t <= 1: + raise ValueError(f"Parameter t must be in range [0, 1], got {t}") + + hsv = rgb_to_hsv(base_rgb) + + # Ramp value: interpolate from 0.75 to 1.0 based on t. + new_v = 0.75 + 0.25 * t + + # Ramp saturation: scale from 85% to 110% of original based on t. + saturation_factor = 0.85 + 0.25 * t + new_s = clamp(hsv.s * saturation_factor) + + new_hsv = HSV(hsv.h, new_s, new_v) + r, g, b = hsv_to_rgb(new_hsv) + + return (r, g, b, alpha) + + +def darken_rgba( + rgba: Tuple[float, float, float, float], factor: float = 0.85 +) -> Tuple[float, float, float, float]: + """Darken an RGBA color by a given factor. + + Args: + rgba: RGBA color tuple with values in range [0, 1]. + factor: Darkening factor in range [0, 1], where 0 is black and 1 is original. + + Returns: + RGBA color tuple with darkened color. + + Raises: + ValueError: If factor is not in range [0, 1]. + """ + if not 0 <= factor <= 1: + raise ValueError(f"Factor must be in range [0, 1], got {factor}") + + r, g, b, a = rgba + return (r * factor, g * factor, b * factor, a) + + +def lighten_rgba( + rgba: Tuple[float, float, float, float], factor: float = 0.15 +) -> Tuple[float, float, float, float]: + """Lighten an RGBA color by interpolating towards white. + + Args: + rgba: RGBA color tuple with values in range [0, 1]. + factor: Lightening factor in range [0, 1], where 0 is original and 1 is white. + + Returns: + RGBA color tuple with lightened color. + + Raises: + ValueError: If factor is not in range [0, 1]. + """ + if not 0 <= factor <= 1: + raise ValueError(f"Factor must be in range [0, 1], got {factor}") + + r, g, b, a = rgba + return (r + (1 - r) * factor, g + (1 - g) * factor, b + (1 - b) * factor, a) + + +def adjust_saturation( + rgb: Tuple[float, float, float], factor: float +) -> Tuple[float, float, float]: + """Adjust the saturation of an RGB color. + + Args: + rgb: RGB color tuple with values in range [0, 1]. + factor: Saturation factor where 0 is grayscale, 1 is original, >1 is more saturated. + + Returns: + RGB color tuple with adjusted saturation. + """ + hsv = rgb_to_hsv(rgb) + new_s = clamp(hsv.s * factor) + new_hsv = HSV(hsv.h, new_s, hsv.v) + return hsv_to_rgb(new_hsv) diff --git a/mjlab/src/mjlab/utils/gpu.py b/mjlab/src/mjlab/utils/gpu.py new file mode 100644 index 0000000000000000000000000000000000000000..244e60382036cf19757c61e4dbb5ee75fba18f29 --- /dev/null +++ b/mjlab/src/mjlab/utils/gpu.py @@ -0,0 +1,74 @@ +"""Utilities for GPU selection and management.""" + +import os +from typing import Literal + + +def select_gpus( + gpu_ids: list[int] | Literal["all"] | None, +) -> tuple[list[int] | None, int]: + """Select GPUs based on CUDA_VISIBLE_DEVICES and user specification. + + This function treats the `gpu_ids` parameter as indices into the existing + CUDA_VISIBLE_DEVICES environment variable. If CUDA_VISIBLE_DEVICES is not set, + it defaults to all available GPUs. + + Args: + gpu_ids: Either a list of GPU indices (into CUDA_VISIBLE_DEVICES), "all", or None + for CPU. + + Returns: + A tuple of (selected_gpu_ids, num_gpus) where: + - selected_gpu_ids: List of physical GPU IDs to use, or None for CPU mode + - num_gpus: Number of GPUs selected (0 for CPU mode) + + Examples: + >>> os.environ["CUDA_VISIBLE_DEVICES"] = "0,1,2,3" + >>> select_gpus([0, 1]) + ([0, 1], 2) + + >>> os.environ["CUDA_VISIBLE_DEVICES"] = "1,3" + >>> select_gpus([0]) # Selects physical GPU 1 + ([1], 1) + + >>> select_gpus("all") # Selects all GPUs in CUDA_VISIBLE_DEVICES + ([1, 3], 2) + + >>> select_gpus(None) # CPU mode + (None, 0) + + >>> os.environ["CUDA_VISIBLE_DEVICES"] = "" # Empty CUDA_VISIBLE_DEVICES + >>> select_gpus([0]) + (None, 0) + """ + # CPU mode requested explicitly. + if gpu_ids is None: + return None, 0 + + # Get existing CUDA_VISIBLE_DEVICES or default to all GPUs. + existing_visible_devices = os.environ.get("CUDA_VISIBLE_DEVICES", None) + + if existing_visible_devices is not None: + # Parse existing CUDA_VISIBLE_DEVICES. + available_gpus = [ + int(x.strip()) for x in existing_visible_devices.split(",") if x.strip() + ] + # Empty CUDA_VISIBLE_DEVICES means CPU mode. + if not available_gpus: + return None, 0 + else: + # If not set, default to all available GPUs. + import torch.cuda + + available_gpus = list(range(torch.cuda.device_count())) + + # Map gpu_ids indices to actual GPU IDs. + if gpu_ids == "all": + selected_gpus = available_gpus + else: + # gpu_ids are indices into available_gpus. + selected_gpus = [available_gpus[i] for i in gpu_ids] + + num_gpus = len(selected_gpus) + + return selected_gpus, num_gpus diff --git a/mjlab/src/mjlab/utils/logging.py b/mjlab/src/mjlab/utils/logging.py new file mode 100644 index 0000000000000000000000000000000000000000..c71f707f152a2963b7395d110f4ca4f10155518f --- /dev/null +++ b/mjlab/src/mjlab/utils/logging.py @@ -0,0 +1,25 @@ +"""Logging utilities for colored terminal output.""" + +import sys + + +def print_info(message: str, color: str = "green") -> None: + """Print information message with color. + + Args: + message: The message to print. + color: Color name ('green', 'red', 'yellow', 'blue', 'cyan', 'magenta'). + """ + colors = { + "green": "\033[92m", + "red": "\033[91m", + "yellow": "\033[93m", + "blue": "\033[94m", + "cyan": "\033[96m", + "magenta": "\033[95m", + } + + if sys.stdout.isatty() and color in colors: + print(f"{colors[color]}{message}\033[0m") + else: + print(message) diff --git a/mjlab/src/mjlab/utils/mujoco.py b/mjlab/src/mjlab/utils/mujoco.py new file mode 100644 index 0000000000000000000000000000000000000000..9a6e084c80805ec5236590415b384ece39e01b71 --- /dev/null +++ b/mjlab/src/mjlab/utils/mujoco.py @@ -0,0 +1,28 @@ +import mujoco + + +def is_position_actuator(actuator: mujoco.MjsActuator) -> bool: + """Check if an actuator is a position actuator. + + This function works on both model.actuator and spec.actuator objects. + """ + return ( + actuator.gaintype == mujoco.mjtGain.mjGAIN_FIXED + and actuator.biastype == mujoco.mjtBias.mjBIAS_AFFINE + and actuator.dyntype in (mujoco.mjtDyn.mjDYN_NONE, mujoco.mjtDyn.mjDYN_FILTEREXACT) + and actuator.gainprm[0] == -actuator.biasprm[1] + ) + + +def dof_width(joint_type: int | mujoco.mjtJoint) -> int: + """Get the dimensionality of the joint in qvel.""" + if isinstance(joint_type, mujoco.mjtJoint): + joint_type = joint_type.value + return {0: 6, 1: 3, 2: 1, 3: 1}[joint_type] + + +def qpos_width(joint_type: int | mujoco.mjtJoint) -> int: + """Get the dimensionality of the joint in qpos.""" + if isinstance(joint_type, mujoco.mjtJoint): + joint_type = joint_type.value + return {0: 7, 1: 4, 2: 1, 3: 1}[joint_type] diff --git a/mjlab/src/mjlab/utils/nan_guard.py b/mjlab/src/mjlab/utils/nan_guard.py new file mode 100644 index 0000000000000000000000000000000000000000..9c77a48968fee9d7d8784f4d16b2abf743808632 --- /dev/null +++ b/mjlab/src/mjlab/utils/nan_guard.py @@ -0,0 +1,187 @@ +"""Lightweight NaN guard for capturing simulation states when NaN/Inf detected.""" + +from collections import deque +from contextlib import contextmanager +from dataclasses import dataclass +from datetime import datetime +from pathlib import Path +from typing import Iterator + +import mujoco +import mujoco_warp as mjwarp +import numpy as np +import torch + + +@dataclass +class NanGuardCfg: + """Configuration for NaN guard.""" + + enabled: bool = False + buffer_size: int = 100 + output_dir: str = "/tmp/mjlab/nan_dumps" + max_envs_to_dump: int = 5 + + +class NanGuard: + """Guards against NaN/Inf by buffering states and dumping on detection. + + When enabled, maintains a rolling buffer of simulation states and writes + them to disk when NaN or Inf is detected. When disabled, all operations + are no-ops with minimal overhead. + """ + + def __init__(self, cfg: NanGuardCfg, num_envs: int, mj_model: mujoco.MjModel) -> None: + self.enabled = cfg.enabled + self.num_envs = num_envs + + if not self.enabled: + return + + self.buffer_size = cfg.buffer_size + self.output_dir = Path(cfg.output_dir) + self.max_envs_to_dump = cfg.max_envs_to_dump + self.buffer: deque = deque(maxlen=self.buffer_size) + self.step_counter = 0 + self._dumped = False + + self.state_size = mujoco.mj_stateSize(mj_model, mujoco.mjtState.mjSTATE_PHYSICS) + self.mj_model = mj_model + self.mj_data = mujoco.MjData(mj_model) + + def capture(self, wp_data: mjwarp.Data) -> None: + """Capture current simulation state to buffer.""" + if not self.enabled: + return + + state = { + "step": self.step_counter, + "qpos": wp_data.qpos.clone(), + "qvel": wp_data.qvel.clone(), + } + if self.mj_model.na > 0: + state["act"] = wp_data.act.clone() + + self.buffer.append(state) + self.step_counter += 1 + + @contextmanager + def watch(self, wp_data: mjwarp.Data) -> Iterator[None]: + """Context manager that captures state before and checks for NaN/Inf after. + + Usage: + with nan_guard.watch(wp_data): + mjwarp.step(wp_model, wp_data) + """ + self.capture(wp_data) + yield + self.check_and_dump(wp_data) + + @staticmethod + def detect_nans(data: mjwarp.Data) -> torch.Tensor: + """Detect NaN/Inf values in physics state (qpos, qvel, qacc, qacc_warmstart). + + Args: + data: MuJoCo simulation data containing physics state. + + Returns: + Boolean tensor where True indicates environments with NaN/Inf values. + """ + tensors_to_check = [ + data.qpos, + data.qvel, + data.qacc, + data.qacc_warmstart, + data.sensordata, + ] + + # Build per-env NaN mask (True if env has NaN/Inf in any tensor). + nan_mask = torch.zeros( + data.qpos.shape[0], dtype=torch.bool, device=data.qpos.device + ) + for t in tensors_to_check: + nan_mask |= torch.isnan(t).any(dim=-1) | torch.isinf(t).any(dim=-1) + + return nan_mask + + def check_and_dump(self, data: mjwarp.Data) -> bool: + """Check for NaN/Inf and dump buffer if detected. + + Returns: + True if NaN/Inf detected and dump occurred, False otherwise. + """ + if not self.enabled or self._dumped: + return False + + nan_mask = self.detect_nans(data) + + if nan_mask.any(): + nan_env_ids = torch.where(nan_mask)[0].cpu().numpy().tolist() + self._dump_buffer(nan_env_ids) + self._dumped = True + return True + + return False + + def _dump_buffer(self, nan_env_ids: list[int]) -> None: + """Write buffered states to disk.""" + self.output_dir.mkdir(parents=True, exist_ok=True) + timestamp = datetime.now().strftime("%Y%m%d_%H%M%S") + filename = self.output_dir / f"nan_dump_{timestamp}.npz" + model_filename = self.output_dir / f"model_{timestamp}.mjb" + + envs_to_dump = nan_env_ids[: self.max_envs_to_dump] + data = {} + for item in self.buffer: + step = item["step"] + qpos = item["qpos"] + qvel = item["qvel"] + act = item.get("act", None) + + states = np.empty((len(envs_to_dump), self.state_size)) + for idx, env_id in enumerate(envs_to_dump): + self.mj_data.qpos[:] = qpos[env_id].cpu().numpy() + self.mj_data.qvel[:] = qvel[env_id].cpu().numpy() + if act is not None: + self.mj_data.act[:] = act[env_id].cpu().numpy() + + mujoco.mj_getState( + self.mj_model, self.mj_data, states[idx], mujoco.mjtState.mjSTATE_PHYSICS + ) + + data[f"states_step_{step:06d}"] = states + + data["_metadata"] = np.array( + { + "num_envs_total": self.num_envs, + "num_envs_dumped": len(envs_to_dump), + "nan_env_ids": nan_env_ids, + "dumped_env_ids": list(envs_to_dump), + "state_size": self.state_size, + "buffer_size": len(self.buffer), + "detection_step": self.step_counter, + "timestamp": timestamp, + "model_file": model_filename.name, + "note": "States captured using mj_getState(mjSTATE_PHYSICS). " + "Use mj_setState to restore. Model saved as MJB for easy reloading.", + }, + dtype=object, + ) + + np.savez_compressed(filename, **data) + mujoco.mj_saveModel(self.mj_model, str(model_filename), None) + + # Create symlinks to latest dumps + latest_dump = self.output_dir / "nan_dump_latest.npz" + latest_model = self.output_dir / "model_latest.mjb" + latest_dump.unlink(missing_ok=True) + latest_model.unlink(missing_ok=True) + latest_dump.symlink_to(filename.name) + latest_model.symlink_to(model_filename.name) + + print(f"[NanGuard] Detected NaN/Inf at step {self.step_counter}") + print(f"[NanGuard] NaN/Inf found in envs: {nan_env_ids[:10]}...") + print(f"[NanGuard] Dumping {len(envs_to_dump)} envs: {envs_to_dump}") + print(f"[NanGuard] Dumped {len(self.buffer)} states to: {filename}") + print(f"[NanGuard] Saved model to: {model_filename}") + print(f"[NanGuard] Latest dump symlinked at: {latest_dump}") diff --git a/mjlab/src/mjlab/utils/os.py b/mjlab/src/mjlab/utils/os.py new file mode 100644 index 0000000000000000000000000000000000000000..a8bb6759085aa38b28af12eb2a4fa32ee7e20562 --- /dev/null +++ b/mjlab/src/mjlab/utils/os.py @@ -0,0 +1,120 @@ +import re +from pathlib import Path +from typing import Any, Dict + +import yaml + + +def update_assets( + assets: Dict[str, Any], + path: str | Path, + meshdir: str | None = None, + glob: str = "*", + recursive: bool = False, +): + """Update assets dictionary with files from a directory. + + This function reads files from a directory and adds them to an assets dictionary, + with keys formatted to include the meshdir prefix when specified. + + Args: + assets: Dictionary to update with file contents. Keys are asset paths, values are + file contents as bytes. + path: Path to directory containing asset files. + meshdir: Optional mesh directory prefix, typically `spec.meshdir`. If provided, + will be prepended to asset keys (e.g., "mesh.obj" becomes "custom_dir/mesh.obj"). + glob: Glob pattern for file matching. Defaults to "*" (all files). + recursive: If True, recursively search subdirectories. + """ + for f in Path(path).glob(glob): + if f.is_file(): + asset_key = f"{meshdir}/{f.name}" if meshdir else f.name + assets[asset_key] = f.read_bytes() + elif f.is_dir() and recursive: + update_assets(assets, f, meshdir, glob, recursive) + + +def dump_yaml(filename: Path, data: Dict, sort_keys: bool = False) -> None: + """Saves data to a YAML file. + + Args: + filename: The path to the YAML file. + data: The data to save. Must be a dictionary. + sort_keys: Whether to sort the keys in the YAML file. + """ + if not filename.suffix: + filename = filename.with_suffix(".yaml") + filename.parent.mkdir(parents=True, exist_ok=True) + with open(filename, "w") as f: + yaml.dump(data, f, sort_keys=sort_keys) + + +def get_checkpoint_path( + log_path: Path, + run_dir: str = ".*", + checkpoint: str = ".*", + sort_alpha: bool = True, +) -> Path: + """Get path to model checkpoint in input directory. + + The checkpoint file is resolved as: `//`. + + If `run_dir` and `checkpoint` are regex expressions, then the most recent + (highest alphabetical order) run and checkpoint are selected. To disable this + behavior, set `sort_alpha` to `False`. + """ + if not log_path.exists(): + raise ValueError(f"Log path does not exist: {log_path}") + # Exclude wandb_checkpoints directory which is used for caching downloaded checkpoints. + runs = [ + log_path / run.name + for run in log_path.iterdir() + if run.is_dir() and run.name != "wandb_checkpoints" and re.match(run_dir, run.name) + ] + if len(runs) == 0: + raise ValueError(f"No run directories found in {log_path} matching '{run_dir}'") + if sort_alpha: + runs.sort() + else: + runs = sorted(runs, key=lambda p: p.stat().st_mtime) + run_path = runs[-1] + + model_checkpoints = [ + f.name for f in run_path.iterdir() if re.match(checkpoint, f.name) + ] + if len(model_checkpoints) == 0: + raise ValueError(f"No checkpoint found in {run_path} matching {checkpoint}") + model_checkpoints.sort(key=lambda m: f"{m:0>15}") + checkpoint_file = model_checkpoints[-1] + return run_path / checkpoint_file + + +def get_wandb_checkpoint_path(log_path: Path, run_path: Path) -> tuple[Path, bool]: + """Get checkpoint path from wandb, downloading if needed. + + Returns: + Tuple of (checkpoint_path, was_cached) + """ + import wandb + + # Extract run_id from path (e.g., "entity/project/run_id" -> "run_id"). + run_id = str(run_path).split("/")[-1] + download_dir = log_path / "wandb_checkpoints" / run_id + + # Query wandb API to find the latest checkpoint. + api = wandb.Api() + wandb_run = api.run(str(run_path)) + files = [ + file.name for file in wandb_run.files() if re.match(r"^model_\d+\.pt$", file.name) + ] + checkpoint_file = max(files, key=lambda x: int(x.split("_")[1].split(".")[0])) + checkpoint_path = download_dir / checkpoint_file + + # If this checkpoint is not cached locally, download it. + was_cached = checkpoint_path.exists() + if not was_cached: + download_dir.mkdir(parents=True, exist_ok=True) + wandb_file = wandb_run.file(str(checkpoint_file)) + wandb_file.download(str(download_dir), replace=True) + + return checkpoint_path, was_cached diff --git a/mjlab/src/mjlab/utils/random.py b/mjlab/src/mjlab/utils/random.py new file mode 100644 index 0000000000000000000000000000000000000000..682a3a056b808d9c66e7d35aef13f188e9eee8ac --- /dev/null +++ b/mjlab/src/mjlab/utils/random.py @@ -0,0 +1,26 @@ +import os +import random + +import numpy as np +import torch +import warp as wp + + +def seed_rng(seed: int, torch_deterministic: bool = False) -> None: + """Seed all random number generators for reproducibility. + + Note: MuJoCo Warp is not fully deterministic yet. + See: https://github.com/google-deepmind/mujoco_warp/issues/562 + """ + os.environ["PYTHONHASHSEED"] = str(seed) + + random.seed(seed) + np.random.seed(seed) + + wp.rand_init(wp.int32(seed)) + + # Ref: https://docs.pytorch.org/docs/stable/notes/randomness.html + torch.manual_seed(seed) # Seed RNG for all devices. + # Use deterministic algorithms when possible. + if torch_deterministic: + torch.use_deterministic_algorithms(True, warn_only=True) diff --git a/mjlab/src/mjlab/utils/spaces.py b/mjlab/src/mjlab/utils/spaces.py new file mode 100644 index 0000000000000000000000000000000000000000..0176801d086bb696a0b6c33b39018bde57d46597 --- /dev/null +++ b/mjlab/src/mjlab/utils/spaces.py @@ -0,0 +1,86 @@ +"""Lightweight space definitions for environment observations and actions. + +This module provides minimal space representations to replace gymnasium.spaces, +focusing only on what mjlab needs (shape and dtype information for batching). +""" + +from __future__ import annotations + +import math +from dataclasses import dataclass, field +from typing import Literal, overload + +from typing_extensions import assert_never + + +@dataclass +class Space: + """Base space class with shape and dtype information.""" + + shape: tuple[int, ...] = () + dtype: Literal["float32", "int32", "int64", "uint8"] = "float32" + + +@dataclass +class Box(Space): + """Continuous space with optional bounds.""" + + low: float | tuple[float, ...] = -math.inf + high: float | tuple[float, ...] = math.inf + + +@dataclass +class Dict(Space): + """Dictionary space containing multiple named subspaces.""" + + spaces: dict[str, Space] = field(default_factory=dict) + + +@overload +def batch_space(space: Dict, batch_size: int) -> Dict: ... + + +@overload +def batch_space(space: Box, batch_size: int) -> Box: ... + + +@overload +def batch_space(space: Space, batch_size: int) -> Space: ... + + +def batch_space(space: Space, batch_size: int) -> Space: + """Create a batched version of a space. + + Prepends batch_size dimension to the space's shape. + + Args: + space: The space to batch + batch_size: Number of parallel environments + + Returns: + New space with batched shape + """ + if isinstance(space, Dict): + # For Dict spaces, batch each subspace. + return Dict( + spaces={ + key: batch_space(subspace, batch_size) for key, subspace in space.spaces.items() + }, + shape=(batch_size,), + dtype=space.dtype, + ) + elif isinstance(space, Box): + # For Box spaces, prepend batch dimension. + batched_shape = (batch_size,) + space.shape + return Box( + shape=batched_shape, + low=space.low, + high=space.high, + dtype=space.dtype, + ) + elif isinstance(space, Space): + # For generic Space, prepend batch dimension. + batched_shape = (batch_size,) + space.shape + return Space(shape=batched_shape, dtype=space.dtype) + else: + assert_never(space) diff --git a/mjlab/src/mjlab/utils/spec.py b/mjlab/src/mjlab/utils/spec.py new file mode 100644 index 0000000000000000000000000000000000000000..0fe216bbc5e91c28568da8cee90572a0dc2bd093 --- /dev/null +++ b/mjlab/src/mjlab/utils/spec.py @@ -0,0 +1,277 @@ +"""MjSpec utils.""" + +from typing import Callable + +import mujoco +import numpy as np + +from mjlab.actuator.actuator import TransmissionType + +_TRANSMISSION_TYPE_MAP = { + TransmissionType.JOINT: mujoco.mjtTrn.mjTRN_JOINT, + TransmissionType.TENDON: mujoco.mjtTrn.mjTRN_TENDON, + TransmissionType.SITE: mujoco.mjtTrn.mjTRN_SITE, +} + + +def auto_wrap_fixed_base_mocap( + spec_fn: Callable[[], mujoco.MjSpec], +) -> Callable[[], mujoco.MjSpec]: + """Wraps spec_fn to auto-wrap fixed-base entities in mocap. + + This enables fixed-base entities to be positioned independently per environment. + Returns original spec unchanged if entity is floating-base or already mocap. + + .. note:: + Mocap wrapping is automatic, but positioning only happens when you call a + reset event (e.g., reset_root_state_uniform). Without a reset event, all + fixed-base robots will remain at the world origin. + + See FAQ: "Why are my fixed-base robots all stacked at the origin?" + """ + + def wrapper() -> mujoco.MjSpec: + original_spec = spec_fn() + + # Check if entity has freejoint (floating-base). + free_joint = get_free_joint(original_spec) + if free_joint is not None: + return original_spec # Floating-base, no wrapping needed. + + # Check if root body is already mocap. + root_body = original_spec.bodies[1] if len(original_spec.bodies) > 1 else None + if root_body and root_body.mocap: + return original_spec # Already mocap, no wrapping needed. + + # Extract and delete keyframes before attach (they transfer but we need + # them on the wrapper spec, not nested in the attached spec). + keyframes = [ + (np.array(k.qpos), np.array(k.ctrl), k.name) for k in original_spec.keys + ] + for k in list(original_spec.keys): + original_spec.delete(k) + + # Wrap in mocap body. + wrapper_spec = mujoco.MjSpec() + mocap_body = wrapper_spec.worldbody.add_body(name="mocap_base", mocap=True) + frame = mocap_body.add_frame() + wrapper_spec.attach(child=original_spec, prefix="", frame=frame) + + # Re-add keyframes to wrapper spec. + for qpos, ctrl, name in keyframes: + wrapper_spec.add_key(name=name, qpos=qpos.tolist(), ctrl=ctrl.tolist()) + + return wrapper_spec + + return wrapper + + +def get_non_free_joints(spec: mujoco.MjSpec) -> tuple[mujoco.MjsJoint, ...]: + """Returns all joints except the free joint.""" + joints: list[mujoco.MjsJoint] = [] + for jnt in spec.joints: + if jnt.type == mujoco.mjtJoint.mjJNT_FREE: + continue + joints.append(jnt) + return tuple(joints) + + +def get_free_joint(spec: mujoco.MjSpec) -> mujoco.MjsJoint | None: + """Returns the free joint. None if no free joint exists.""" + joint: mujoco.MjsJoint | None = None + for jnt in spec.joints: + if jnt.type == mujoco.mjtJoint.mjJNT_FREE: + joint = jnt + break + return joint + + +def disable_collision(geom: mujoco.MjsGeom) -> None: + """Disables collision for a geom.""" + geom.contype = 0 + geom.conaffinity = 0 + + +def is_joint_limited(jnt: mujoco.MjsJoint) -> bool: + """Returns True if a joint is limited.""" + match jnt.limited: + case mujoco.mjtLimited.mjLIMITED_TRUE: + return True + case mujoco.mjtLimited.mjLIMITED_AUTO: + return jnt.range[0] < jnt.range[1] + case _: + return False + + +def create_motor_actuator( + spec: mujoco.MjSpec, + joint_name: str, + *, + effort_limit: float, + gear: float = 1.0, + armature: float = 0.0, + frictionloss: float = 0.0, + transmission_type: TransmissionType = TransmissionType.JOINT, +) -> mujoco.MjsActuator: + """Create a actuator.""" + actuator = spec.add_actuator(name=joint_name, target=joint_name) + + actuator.trntype = _TRANSMISSION_TYPE_MAP[transmission_type] + actuator.dyntype = mujoco.mjtDyn.mjDYN_NONE + actuator.gaintype = mujoco.mjtGain.mjGAIN_FIXED + actuator.biastype = mujoco.mjtBias.mjBIAS_NONE + + actuator.gear[0] = gear + # Technically redundant to set both but being explicit here. + actuator.forcelimited = True + actuator.forcerange[:] = np.array([-effort_limit, effort_limit]) + actuator.ctrllimited = True + actuator.ctrlrange[:] = np.array([-effort_limit, effort_limit]) + + # Set armature and frictionloss. + if transmission_type == TransmissionType.JOINT: + spec.joint(joint_name).armature = armature + spec.joint(joint_name).frictionloss = frictionloss + elif transmission_type == TransmissionType.TENDON: + spec.tendon(joint_name).armature = armature + spec.tendon(joint_name).frictionloss = frictionloss + + return actuator + + +def create_position_actuator( + spec: mujoco.MjSpec, + joint_name: str, + *, + stiffness: float, + damping: float, + effort_limit: float | None = None, + armature: float = 0.0, + frictionloss: float = 0.0, + transmission_type: TransmissionType = TransmissionType.JOINT, +) -> mujoco.MjsActuator: + """Creates a actuator. + + An important note about this actuator is that we set `ctrllimited` to False. This is + because we want to allow the policy to output setpoints that are outside the kinematic + limits of the joint. + """ + actuator = spec.add_actuator(name=joint_name, target=joint_name) + + actuator.trntype = _TRANSMISSION_TYPE_MAP[transmission_type] + actuator.dyntype = mujoco.mjtDyn.mjDYN_NONE + actuator.gaintype = mujoco.mjtGain.mjGAIN_FIXED + actuator.biastype = mujoco.mjtBias.mjBIAS_AFFINE + + # Set stiffness and damping. + actuator.gainprm[0] = stiffness + actuator.biasprm[1] = -stiffness + actuator.biasprm[2] = -damping + + # Limits. + actuator.ctrllimited = False + # No ctrlrange needed. + if effort_limit is not None: + actuator.forcelimited = True + actuator.forcerange[:] = np.array([-effort_limit, effort_limit]) + else: + actuator.forcelimited = False + # No forcerange needed. + + # Set armature and frictionloss. + if transmission_type == TransmissionType.JOINT: + spec.joint(joint_name).armature = armature + spec.joint(joint_name).frictionloss = frictionloss + elif transmission_type == TransmissionType.TENDON: + spec.tendon(joint_name).armature = armature + spec.tendon(joint_name).frictionloss = frictionloss + + return actuator + + +def create_velocity_actuator( + spec: mujoco.MjSpec, + joint_name: str, + *, + damping: float, + effort_limit: float | None = None, + armature: float = 0.0, + frictionloss: float = 0.0, + inheritrange: float = 1.0, + transmission_type: TransmissionType = TransmissionType.JOINT, +) -> mujoco.MjsActuator: + """Creates a actuator.""" + actuator = spec.add_actuator(name=joint_name, target=joint_name) + + actuator.trntype = _TRANSMISSION_TYPE_MAP[transmission_type] + actuator.dyntype = mujoco.mjtDyn.mjDYN_NONE + actuator.gaintype = mujoco.mjtGain.mjGAIN_FIXED + actuator.biastype = mujoco.mjtBias.mjBIAS_AFFINE + + actuator.inheritrange = inheritrange + actuator.ctrllimited = True # Technically redundant but being explicit. + actuator.gainprm[0] = damping + actuator.biasprm[2] = -damping + + if effort_limit is not None: + # Will this throw an error with autolimits=True? + actuator.forcelimited = True + actuator.forcerange[:] = np.array([-effort_limit, effort_limit]) + else: + actuator.forcelimited = False + + if transmission_type == TransmissionType.JOINT: + spec.joint(joint_name).armature = armature + spec.joint(joint_name).frictionloss = frictionloss + elif transmission_type == TransmissionType.TENDON: + spec.tendon(joint_name).armature = armature + spec.tendon(joint_name).frictionloss = frictionloss + + return actuator + + +def create_muscle_actuator( + spec: mujoco.MjSpec, + target_name: str, + *, + length_range: tuple[float, float] = (0.0, 0.0), + gear: float = 1.0, + timeconst: tuple[float, float] = (0.01, 0.04), + tausmooth: float = 0.0, + range: tuple[float, float] = (0.75, 1.05), + force: float = -1.0, + scale: float = 200.0, + lmin: float = 0.5, + lmax: float = 1.6, + vmax: float = 1.5, + fpmax: float = 1.3, + fvmax: float = 1.2, + transmission_type: TransmissionType = TransmissionType.TENDON, +) -> mujoco.MjsActuator: + """Create a MuJoCo actuator with muscle dynamics. + + Muscles use special activation dynamics and force-length-velocity curves. + They can actuate tendons or joints. + """ + actuator = spec.add_actuator(name=target_name, target=target_name) + + if transmission_type not in [TransmissionType.JOINT, TransmissionType.TENDON]: + raise ValueError("Muscle actuators only support JOINT and TENDON transmissions.") + actuator.trntype = _TRANSMISSION_TYPE_MAP[transmission_type] + actuator.dyntype = mujoco.mjtDyn.mjDYN_MUSCLE + actuator.gaintype = mujoco.mjtGain.mjGAIN_MUSCLE + actuator.biastype = mujoco.mjtBias.mjBIAS_MUSCLE + + actuator.gear[0] = gear + actuator.dynprm[0:3] = np.array([*timeconst, tausmooth]) + actuator.gainprm[0:9] = np.array( + [*range, force, scale, lmin, lmax, vmax, fpmax, fvmax] + ) + actuator.biasprm[:] = actuator.gainprm[:] + actuator.lengthrange[0:2] = length_range + + # TODO(kevin): Double check this. + actuator.ctrllimited = True + actuator.ctrlrange[:] = np.array([0.0, 1.0]) + + return actuator diff --git a/mjlab/src/mjlab/utils/spec_config.py b/mjlab/src/mjlab/utils/spec_config.py new file mode 100644 index 0000000000000000000000000000000000000000..018080f367f897d7ef4a2112821b33c0d8305ba5 --- /dev/null +++ b/mjlab/src/mjlab/utils/spec_config.py @@ -0,0 +1,322 @@ +from abc import ABC, abstractmethod +from dataclasses import dataclass +from typing import Literal + +import mujoco + +_TYPE_MAP = { + "2d": mujoco.mjtTexture.mjTEXTURE_2D, + "cube": mujoco.mjtTexture.mjTEXTURE_CUBE, + "skybox": mujoco.mjtTexture.mjTEXTURE_SKYBOX, +} +_BUILTIN_MAP = { + "checker": mujoco.mjtBuiltin.mjBUILTIN_CHECKER, + "gradient": mujoco.mjtBuiltin.mjBUILTIN_GRADIENT, + "flat": mujoco.mjtBuiltin.mjBUILTIN_FLAT, + "none": mujoco.mjtBuiltin.mjBUILTIN_NONE, +} +_MARK_MAP = { + "edge": mujoco.mjtMark.mjMARK_EDGE, + "cross": mujoco.mjtMark.mjMARK_CROSS, + "random": mujoco.mjtMark.mjMARK_RANDOM, + "none": mujoco.mjtMark.mjMARK_NONE, +} + +_GEOM_ATTR_DEFAULTS = { + "condim": 3, + "contype": 1, + "conaffinity": 1, + "priority": 0, + "friction": None, + "solref": None, + "solimp": None, +} + +_LIGHT_TYPE_MAP = { + "directional": mujoco.mjtLightType.mjLIGHT_DIRECTIONAL, + "spot": mujoco.mjtLightType.mjLIGHT_SPOT, +} + +_CAM_LIGHT_MODE_MAP = { + "fixed": mujoco.mjtCamLight.mjCAMLIGHT_FIXED, + "track": mujoco.mjtCamLight.mjCAMLIGHT_TRACK, + "trackcom": mujoco.mjtCamLight.mjCAMLIGHT_TRACKCOM, + "targetbody": mujoco.mjtCamLight.mjCAMLIGHT_TARGETBODY, + "targetbodycom": mujoco.mjtCamLight.mjCAMLIGHT_TARGETBODYCOM, +} + + +@dataclass +class SpecCfg(ABC): + """Base class for all MuJoCo spec configurations.""" + + @abstractmethod + def edit_spec(self, spec: mujoco.MjSpec) -> None: + raise NotImplementedError + + def validate(self) -> None: # noqa: B027 + """Optional validation method to be overridden by subclasses.""" + pass + + +@dataclass +class TextureCfg(SpecCfg): + """Configuration to add a texture to the MuJoCo spec.""" + + name: str + """Name of the texture.""" + type: Literal["2d", "cube", "skybox"] + """Texture type ("2d", "cube", or "skybox").""" + builtin: Literal["checker", "gradient", "flat", "none"] + """Built-in texture pattern ("checker", "gradient", "flat", or "none").""" + rgb1: tuple[float, float, float] + """First RGB color tuple.""" + rgb2: tuple[float, float, float] + """Second RGB color tuple.""" + width: int + """Texture width in pixels (must be positive).""" + height: int + """Texture height in pixels (must be positive).""" + mark: Literal["edge", "cross", "random", "none"] = "none" + """Marking pattern ("edge", "cross", "random", or "none").""" + markrgb: tuple[float, float, float] = (0.0, 0.0, 0.0) + """RGB color for markings.""" + + def edit_spec(self, spec: mujoco.MjSpec) -> None: + self.validate() + + spec.add_texture( + name=self.name, + type=_TYPE_MAP[self.type], + builtin=_BUILTIN_MAP[self.builtin], + mark=_MARK_MAP[self.mark], + rgb1=self.rgb1, + rgb2=self.rgb2, + markrgb=self.markrgb, + width=self.width, + height=self.height, + ) + + def validate(self) -> None: + if self.width <= 0 or self.height <= 0: + raise ValueError("Texture width and height must be positive.") + + +@dataclass +class MaterialCfg(SpecCfg): + """Configuration to add a material to the MuJoCo spec.""" + + name: str + """Name of the material.""" + texuniform: bool + """Whether texture is uniform.""" + texrepeat: tuple[int, int] + """Texture repeat pattern (width, height) - both must be positive.""" + reflectance: float = 0.0 + """Material reflectance value.""" + texture: str | None = None + """Name of texture to apply (optional).""" + + def edit_spec(self, spec: mujoco.MjSpec) -> None: + self.validate() + + mat = spec.add_material( + name=self.name, + texuniform=self.texuniform, + texrepeat=self.texrepeat, + ) + if self.texture is not None: + mat.textures[mujoco.mjtTextureRole.mjTEXROLE_RGB.value] = self.texture + + def validate(self) -> None: + if self.texrepeat[0] <= 0 or self.texrepeat[1] <= 0: + raise ValueError("Material texrepeat values must be positive.") + + +@dataclass +class CollisionCfg(SpecCfg): + """Configuration to modify collision properties of geoms in the MuJoCo spec. + + Supports regex pattern matching for geom names and dict-based field resolution + for fine-grained control over collision properties. + """ + + geom_names_expr: tuple[str, ...] + """Tuple of regex patterns to match geom names.""" + contype: int | dict[str, int] = 1 + """Collision type (int or dict mapping patterns to values). Must be non-negative.""" + conaffinity: int | dict[str, int] = 1 + """Collision affinity (int or dict mapping patterns to values). Must be + non-negative.""" + condim: int | dict[str, int] = 3 + """Contact dimension (int or dict mapping patterns to values). Must be one + of {1, 3, 4, 6}.""" + priority: int | dict[str, int] = 0 + """Collision priority (int or dict mapping patterns to values). Must be + non-negative.""" + friction: tuple[float, ...] | dict[str, tuple[float, ...]] | None = None + """Friction coefficients as tuple or dict mapping patterns to tuples.""" + solref: tuple[float, ...] | dict[str, tuple[float, ...]] | None = None + """Solver reference parameters as tuple or dict mapping patterns to tuples.""" + solimp: tuple[float, ...] | dict[str, tuple[float, ...]] | None = None + """Solver impedance parameters as tuple or dict mapping patterns to tuples.""" + disable_other_geoms: bool = True + """Whether to disable collision for non-matching geoms.""" + + @staticmethod + def set_array_field(field, values): + if values is None: + return + for i, v in enumerate(values): + field[i] = v + + def validate(self) -> None: + """Validate collision configuration parameters.""" + valid_condim = {1, 3, 4, 6} + + # Validate condim specifically (has special valid values). + if isinstance(self.condim, int): + if self.condim not in valid_condim: + raise ValueError(f"condim must be one of {valid_condim}, got {self.condim}") + elif isinstance(self.condim, dict): + for pattern, value in self.condim.items(): + if value not in valid_condim: + raise ValueError( + f"condim must be one of {valid_condim}, got {value} for pattern '{pattern}'" + ) + + # Validate other int parameters. + if isinstance(self.contype, int) and self.contype < 0: + raise ValueError("contype must be non-negative") + if isinstance(self.conaffinity, int) and self.conaffinity < 0: + raise ValueError("conaffinity must be non-negative") + if isinstance(self.priority, int) and self.priority < 0: + raise ValueError("priority must be non-negative") + + # Validate dict parameters (excluding condim which is handled above). + for field_name in ["contype", "conaffinity", "priority"]: + field_value = getattr(self, field_name) + if isinstance(field_value, dict): + for pattern, value in field_value.items(): + if value < 0: + raise ValueError( + f"{field_name} must be non-negative, got {value} for pattern '{pattern}'" + ) + + def edit_spec(self, spec: mujoco.MjSpec) -> None: + from mjlab.utils.spec import disable_collision + from mjlab.utils.string import filter_exp, resolve_field + + self.validate() + + all_geoms: list[mujoco.MjsGeom] = spec.geoms + all_geom_names = tuple(g.name for g in all_geoms) + geom_subset = filter_exp(self.geom_names_expr, all_geom_names) + + resolved_fields = { + name: resolve_field(getattr(self, name), geom_subset, default) + for name, default in _GEOM_ATTR_DEFAULTS.items() + } + + for i, geom_name in enumerate(geom_subset): + geom = spec.geom(geom_name) + + geom.condim = resolved_fields["condim"][i] + geom.contype = resolved_fields["contype"][i] + geom.conaffinity = resolved_fields["conaffinity"][i] + geom.priority = resolved_fields["priority"][i] + + CollisionCfg.set_array_field(geom.friction, resolved_fields["friction"][i]) + CollisionCfg.set_array_field(geom.solref, resolved_fields["solref"][i]) + CollisionCfg.set_array_field(geom.solimp, resolved_fields["solimp"][i]) + + if self.disable_other_geoms: + other_geoms = set(all_geom_names).difference(geom_subset) + for geom_name in other_geoms: + geom = spec.geom(geom_name) + disable_collision(geom) + + +@dataclass +class LightCfg(SpecCfg): + """Configuration to add a light to the MuJoCo spec.""" + + name: str | None = None + """Name of the light (optional).""" + body: str = "world" + """Body to attach light to (default: "world").""" + mode: str = "fixed" + """Light mode ("fixed", "track", "trackcom", "targetbody", "targetbodycom").""" + target: str | None = None + """Target body for tracking modes (optional).""" + type: Literal["spot", "directional"] = "spot" + """Light type ("spot" or "directional").""" + castshadow: bool = True + """Whether light casts shadows.""" + pos: tuple[float, float, float] = (0, 0, 0) + """Light position (x, y, z).""" + dir: tuple[float, float, float] = (0, 0, -1) + """Light direction vector (x, y, z).""" + cutoff: float = 45 + """Spot light cutoff angle in degrees.""" + exponent: float = 10 + """Spot light exponent.""" + + def edit_spec(self, spec: mujoco.MjSpec) -> None: + self.validate() + + if self.body == "world": + body = spec.worldbody + else: + body = spec.body(self.body) + light = body.add_light( + mode=_CAM_LIGHT_MODE_MAP[self.mode], + type=_LIGHT_TYPE_MAP[self.type], + castshadow=self.castshadow, + pos=self.pos, + dir=self.dir, + cutoff=self.cutoff, + exponent=self.exponent, + ) + if self.name is not None: + light.name = self.name + if self.target is not None: + light.targetbody = self.target + + +@dataclass +class CameraCfg(SpecCfg): + """Configuration to add a camera to the MuJoCo spec.""" + + name: str + """Name of the camera.""" + body: str = "world" + """Body to attach camera to (default: "world").""" + mode: str = "fixed" + """Camera mode ("fixed", "track", "trackcom", "targetbody", "targetbodycom").""" + target: str | None = None + """Target body for tracking modes (optional).""" + fovy: float = 45 + """Field of view in degrees.""" + pos: tuple[float, float, float] = (0, 0, 0) + """Camera position (x, y, z).""" + quat: tuple[float, float, float, float] = (1, 0, 0, 0) + """Camera orientation quaternion (w, x, y, z).""" + + def edit_spec(self, spec: mujoco.MjSpec) -> None: + self.validate() + + if self.body == "world": + body = spec.worldbody + else: + body = spec.body(self.body) + camera = body.add_camera( + mode=_CAM_LIGHT_MODE_MAP[self.mode], + fovy=self.fovy, + pos=self.pos, + quat=self.quat, + ) + if self.name is not None: + camera.name = self.name + if self.target is not None: + camera.targetbody = self.target diff --git a/mjlab/src/mjlab/utils/string.py b/mjlab/src/mjlab/utils/string.py new file mode 100644 index 0000000000000000000000000000000000000000..e57d55c0364e2348b6ee34c6a3ab400fb81f59f6 --- /dev/null +++ b/mjlab/src/mjlab/utils/string.py @@ -0,0 +1,38 @@ +import re +from typing import Any + + +def resolve_expr( + pattern_map: dict[str, Any], + names: tuple[str, ...], + default_val: Any = None, +) -> tuple[Any, ...]: + """Resolve a field value (scalar or dict) to a tuple of values matched by patterns.""" + patterns = [(re.compile(pat), val) for pat, val in pattern_map.items()] + + result = [] + for name in names: + for pat, val in patterns: + if pat.match(name): + result.append(val) + break + else: + result.append(default_val) + return tuple(result) + + +def filter_exp( + exprs: list[str] | tuple[str, ...], names: tuple[str, ...] +) -> tuple[str, ...]: + """Filter names based on regex patterns.""" + patterns = [re.compile(expr) for expr in exprs] + return tuple(name for name in names if any(pat.match(name) for pat in patterns)) + + +def resolve_field( + field: Any, names: tuple[str, ...], default_val: Any = None +) -> tuple[Any, ...]: + if isinstance(field, dict): + return resolve_expr(field, names, default_val) + else: + return tuple([field] * len(names)) diff --git a/mjlab/src/mjlab/utils/torch.py b/mjlab/src/mjlab/utils/torch.py new file mode 100644 index 0000000000000000000000000000000000000000..4275bf49be4759fa017f4de30d30e27643bbaa1a --- /dev/null +++ b/mjlab/src/mjlab/utils/torch.py @@ -0,0 +1,41 @@ +import torch +from packaging.version import parse + + +def configure_torch_backends(allow_tf32: bool = True, deterministic: bool = False): + """Configure PyTorch CUDA and cuDNN backends for performance/reproducibility. + + Args: + allow_tf32: If True, use TF32 precision for faster computation on Ampere+ GPUs. If + False, use standard IEEE FP32 precision. + deterministic: If True, use deterministic algorithms (slower but reproducible). + If False, allow cuDNN to benchmark and select fastest algorithms. + + Note: + TF32 uses reduced precision (10-bit mantissa vs 23-bit for FP32) for internal + matrix multiplications providing a speedup with minimal impact on accuracy. + + See https://pytorch.org/docs/stable/notes/cuda.html#tf32-on-ampere for details. + """ + torch_version = parse(torch.__version__.split("+")[0]) # Handle e.g., "2.9.0+cu118". + if torch_version >= parse("2.9.0"): + _configure_29(allow_tf32) + else: + _configure_pre29(allow_tf32) + + torch.backends.cudnn.benchmark = not deterministic # Find fastest algorithms. + torch.backends.cudnn.deterministic = deterministic # Ensure reproducibility. + + +def _configure_29(allow_tf32: bool): + """Configure PyTorch CUDA and cuDNN backends for PyTorch 2.9+.""" + # tf32 for performance, ieee for full FP32 accuracy. + precision = "tf32" if allow_tf32 else "ieee" + torch.backends.cuda.matmul.fp32_precision = precision + torch.backends.cudnn.fp32_precision = precision # type: ignore + + +def _configure_pre29(allow_tf32: bool): + """Configure PyTorch CUDA and cuDNN backends for PyTorch <2.9.""" + torch.backends.cuda.matmul.allow_tf32 = allow_tf32 + torch.backends.cudnn.allow_tf32 = allow_tf32 diff --git a/mjlab/src/mjlab/utils/wandb.py b/mjlab/src/mjlab/utils/wandb.py new file mode 100644 index 0000000000000000000000000000000000000000..177552004181be95d78cfa3a859e5232e3e0c97f --- /dev/null +++ b/mjlab/src/mjlab/utils/wandb.py @@ -0,0 +1,34 @@ +"""WandB utilities.""" + +from __future__ import annotations + +import os +from typing import Sequence + + +def add_wandb_tags(tags: Sequence[str]) -> None: + """Add tags to the current wandb run. + + Note: This function stores tags in wandb.config._wandb_tags if the run is not yet + initialized, allowing them to be retrieved later. If the run is already initialized, + tags are added directly. + """ + if not tags: + return + + try: + import wandb + + if wandb.run is not None: + existing_tags = list(wandb.run.tags) if wandb.run.tags else [] + new_tags = list(set(existing_tags + list(tags))) + wandb.run.tags = new_tags + else: + # Store tags to be added when run is initialized. + # This is a workaround for lazy wandb initialization in rsl_rl 3.1.0. + current_tags = os.environ.get("WANDB_TAGS", "") + all_tags = set(current_tags.split(",") if current_tags else []) + all_tags.update(tags) + os.environ["WANDB_TAGS"] = ",".join(sorted(all_tags)) + except ImportError: + pass diff --git a/mjlab/src/mjlab/viewer/__init__.py b/mjlab/src/mjlab/viewer/__init__.py new file mode 100644 index 0000000000000000000000000000000000000000..c0d6756382abd0a725399ed754b7f469cac7c741 --- /dev/null +++ b/mjlab/src/mjlab/viewer/__init__.py @@ -0,0 +1,10 @@ +"""Viewer module for environment visualization.""" + +from mjlab.viewer.base import BaseViewer as BaseViewer +from mjlab.viewer.base import EnvProtocol as EnvProtocol +from mjlab.viewer.base import PolicyProtocol as PolicyProtocol +from mjlab.viewer.base import VerbosityLevel as VerbosityLevel +from mjlab.viewer.native import NativeMujocoViewer as NativeMujocoViewer +from mjlab.viewer.offscreen_renderer import OffscreenRenderer as OffscreenRenderer +from mjlab.viewer.viewer_config import ViewerConfig as ViewerConfig +from mjlab.viewer.viser import ViserPlayViewer as ViserPlayViewer diff --git a/mjlab/src/mjlab/viewer/base.py b/mjlab/src/mjlab/viewer/base.py new file mode 100644 index 0000000000000000000000000000000000000000..7b01ee091e324d5e1a960e7c0c2f361ef23ac9fc --- /dev/null +++ b/mjlab/src/mjlab/viewer/base.py @@ -0,0 +1,321 @@ +"""Base class for environment viewers.""" + +from __future__ import annotations + +import contextlib +import time +from abc import ABC, abstractmethod +from collections import deque +from enum import Enum, IntEnum +from typing import TYPE_CHECKING, Any, Optional, Protocol + +import torch + +if TYPE_CHECKING: + from mjlab.envs import ManagerBasedRlEnvCfg + + +class VerbosityLevel(IntEnum): + SILENT = 0 + INFO = 1 + DEBUG = 2 + + +class Timer: + def __init__(self): + self._previous_time = time.time() + self._measured_time = 0.0 + + def tick(self): + curr_time = time.time() + self._measured_time = curr_time - self._previous_time + self._previous_time = curr_time + return self._measured_time + + @contextlib.contextmanager + def measure_time(self): + start_time = time.time() + yield + self._measured_time = time.time() - start_time + + @property + def measured_time(self): + return self._measured_time + + +class EnvProtocol(Protocol): + """Interface we expect from RL environments, which can be either vanilla + `ManagerBasedRlEnv` objects or wrapped with `VideoRecorder`, + `RslRlVecEnvWrapper`, etc.""" + + num_envs: int + + @property + def device(self) -> torch.device | str: ... + + @property + def cfg(self) -> ManagerBasedRlEnvCfg: ... + + @property + def unwrapped(self) -> Any: ... + + def get_observations(self) -> Any: ... + def step(self, actions: torch.Tensor) -> tuple[Any, ...]: ... + def reset(self) -> Any: ... + def close(self) -> None: ... + + +class PolicyProtocol(Protocol): + def __call__(self, obs: torch.Tensor) -> torch.Tensor: ... + + +class ViewerAction(Enum): + RESET = "reset" + TOGGLE_PAUSE = "toggle_pause" + SPEED_UP = "speed_up" + SPEED_DOWN = "speed_down" + PREV_ENV = "prev_env" + NEXT_ENV = "next_env" + CUSTOM = "custom" + + +class BaseViewer(ABC): + """Abstract base class for environment viewers.""" + + SPEED_MULTIPLIERS = [0.01, 0.016, 0.025, 0.04, 0.063, 0.1, 0.16, 0.25, 0.4, 0.63, 1.0] + + def __init__( + self, + env: EnvProtocol, + policy: PolicyProtocol, + frame_rate: float = 30.0, + verbosity: int = VerbosityLevel.SILENT, + ): + self.env = env + self.policy = policy + self.frame_rate = frame_rate + self.frame_time = 1.0 / frame_rate + self.verbosity = VerbosityLevel(verbosity) + self.cfg = env.cfg.viewer + + # Loop state. + self._is_paused = False + self._step_count = 0 + + # Timing. + self._timer = Timer() + self._sim_timer = Timer() + self._render_timer = Timer() + self._time_until_next_frame = 0.0 + + self._speed_index = self.SPEED_MULTIPLIERS.index(1.0) + self._time_multiplier = self.SPEED_MULTIPLIERS[self._speed_index] + + # Perf tracking. + self._frame_count = 0 + self._last_fps_log_time = 0.0 + self._accumulated_sim_time = 0.0 + self._accumulated_render_time = 0.0 + + # FPS tracking. + self._smoothed_fps: float = 0.0 + self._fps_accum_frames: int = 0 + self._fps_accum_time: float = 0.0 + self._fps_last_frame_time: Optional[float] = None + self._fps_update_interval: float = 0.5 + self._fps_alpha: float = 0.35 + + # Thread-safe action queue (drained in main loop). + self._actions: deque[tuple[ViewerAction, Optional[Any]]] = deque() + + # Abstract hooks every concrete viewer must implement. + + @abstractmethod + def setup(self) -> None: ... + @abstractmethod + def sync_env_to_viewer(self) -> None: ... + @abstractmethod + def sync_viewer_to_env(self) -> None: ... + @abstractmethod + def close(self) -> None: ... + @abstractmethod + def is_running(self) -> bool: ... + + # Logging. + + def log(self, message: str, level: VerbosityLevel = VerbosityLevel.INFO) -> None: + if self.verbosity >= level: + print(message) + + # Public controls. + + def request_reset(self) -> None: + self._actions.append((ViewerAction.RESET, None)) + + def request_toggle_pause(self) -> None: + self._actions.append((ViewerAction.TOGGLE_PAUSE, None)) + + def request_speed_up(self) -> None: + self._actions.append((ViewerAction.SPEED_UP, None)) + + def request_speed_down(self) -> None: + self._actions.append((ViewerAction.SPEED_DOWN, None)) + + def request_action(self, name: str, payload: Optional[Any] = None) -> None: + """Viewer-specific actions (e.g., PREV_ENV/NEXT_ENV for native).""" + try: + action = ViewerAction[name] + except KeyError: + action = ViewerAction.CUSTOM + self._actions.append((action, payload)) + + # Core loop. + + def step_simulation(self) -> None: + if self._is_paused: + return + # Wrap in no_grad mode to prevent gradient accumulation and memory leaks. + # NOTE: Using torch.inference_mode() causes a "RuntimeError: Inplace update to + # inference tensor outside InferenceMode is not allowed" inside the command + # manager when resetting the env with a key callback. + with torch.no_grad(): + with self._sim_timer.measure_time(): + obs = self.env.get_observations() + actions = self.policy(obs) + self.env.step(actions) + self._step_count += 1 + self._accumulated_sim_time += self._sim_timer.measured_time + + def reset_environment(self) -> None: + self.env.reset() + self._step_count = 0 + self._timer.tick() + + def pause(self) -> None: + self._is_paused = True + self._fps_last_frame_time = None + self.log("[INFO] Simulation paused", VerbosityLevel.INFO) + + def resume(self) -> None: + self._is_paused = False + self._timer.tick() + self._fps_last_frame_time = time.time() + self.log("[INFO] Simulation resumed", VerbosityLevel.INFO) + + def toggle_pause(self) -> None: + if self._is_paused: + self.resume() + else: + self.pause() + + def _process_actions(self) -> None: + """Drain action queue. Runs on the main loop thread.""" + while self._actions: + action, payload = self._actions.popleft() + if action == ViewerAction.RESET: + self.reset_environment() + elif action == ViewerAction.TOGGLE_PAUSE: + self.toggle_pause() + elif action == ViewerAction.SPEED_UP: + self.increase_speed() + elif action == ViewerAction.SPEED_DOWN: + self.decrease_speed() + else: + # Hook for subclasses to handle PREV_ENV/NEXT_ENV or CUSTOM actions + _ = self._handle_custom_action(action, payload) + + def _handle_custom_action(self, action: ViewerAction, payload: Optional[Any]) -> bool: + del action, payload # Unused. + return False + + def tick(self) -> bool: + self._process_actions() + + elapsed_time = self._timer.tick() * self._time_multiplier + self._time_until_next_frame -= elapsed_time + + if self._time_until_next_frame > 0: + return False + + self._time_until_next_frame += self.frame_time + if self._time_until_next_frame < -self.frame_time: + self._time_until_next_frame = 0.0 + + with self._render_timer.measure_time(): + self.sync_viewer_to_env() + self.step_simulation() + self.sync_env_to_viewer() + + self._accumulated_render_time += self._render_timer.measured_time + self._frame_count += 1 + self._update_fps() + + if self.verbosity >= VerbosityLevel.DEBUG: + now = time.time() + if now - self._last_fps_log_time >= 1.0: + self.log_performance() + self._last_fps_log_time = now + self._frame_count = 0 + self._accumulated_sim_time = 0.0 + self._accumulated_render_time = 0.0 + + return True + + def run(self, num_steps: Optional[int] = None) -> None: + self.setup() + self._last_fps_log_time = time.time() + self._timer.tick() + self._fps_last_frame_time = time.time() + try: + while self.is_running() and (num_steps is None or self._step_count < num_steps): + if not self.tick(): + time.sleep(0.001) + finally: + self.close() + + def log_performance(self) -> None: + if self._frame_count > 0: + avg_sim_ms = self._accumulated_sim_time / self._frame_count * 1000 + avg_render_ms = self._accumulated_render_time / self._frame_count * 1000 + total_ms = avg_sim_ms + avg_render_ms + status = "PAUSED" if self._is_paused else "RUNNING" + speed = f"{self._time_multiplier:.1f}x" if self._time_multiplier != 1.0 else "1x" + print( + f"[{status}] Step {self._step_count} | FPS: {self._frame_count:.1f} | " + f"Speed: {speed} | Sim: {avg_sim_ms:.1f}ms | Render: {avg_render_ms:.1f}ms | " + f"Total: {total_ms:.1f}ms" + ) + + def increase_speed(self) -> None: + if self._speed_index < len(self.SPEED_MULTIPLIERS) - 1: + self._speed_index += 1 + self._time_multiplier = self.SPEED_MULTIPLIERS[self._speed_index] + + def decrease_speed(self) -> None: + if self._speed_index > 0: + self._speed_index -= 1 + self._time_multiplier = self.SPEED_MULTIPLIERS[self._speed_index] + + def _update_fps(self) -> None: + if self._is_paused: + return + now = time.time() + if self._fps_last_frame_time is None: + self._fps_last_frame_time = now + return + dt = now - self._fps_last_frame_time + self._fps_last_frame_time = now + if dt <= 0: + return + self._fps_accum_frames += 1 + self._fps_accum_time += dt + if self._fps_accum_time >= self._fps_update_interval: + inst = self._fps_accum_frames / self._fps_accum_time + if self._smoothed_fps == 0.0: + self._smoothed_fps = inst + else: + self._smoothed_fps = ( + self._fps_alpha * inst + (1.0 - self._fps_alpha) * self._smoothed_fps + ) + self._fps_accum_frames = 0 + self._fps_accum_time = 0.0 diff --git a/mjlab/src/mjlab/viewer/debug_visualizer.py b/mjlab/src/mjlab/viewer/debug_visualizer.py new file mode 100644 index 0000000000000000000000000000000000000000..853830554630b991690a38d5262104cf0735cefe --- /dev/null +++ b/mjlab/src/mjlab/viewer/debug_visualizer.py @@ -0,0 +1,224 @@ +"""Abstract interface for debug visualization across different viewers.""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from collections.abc import Iterable +from typing import TYPE_CHECKING + +import numpy as np +import torch + +if TYPE_CHECKING: + import mujoco + + +class DebugVisualizer(ABC): + """Abstract base class for viewer-agnostic debug visualization. + + This allows manager terms to draw debug visualizations without knowing the underlying + viewer implementation. + """ + + env_idx: int + """Index of the environment being visualized.""" + + show_all_envs: bool + """If True, visualize all environments instead of just env_idx.""" + + def get_env_indices(self, num_envs: int) -> Iterable[int]: + """Get the environment indices to visualize. + + This helper method handles the show_all_envs logic so implementations + don't need to repeat this boilerplate. + + Args: + num_envs: Total number of environments. + + Returns: + An iterable of environment indices to visualize. + """ + if self.show_all_envs: + return range(num_envs) + elif self.env_idx < num_envs: + return [self.env_idx] + else: + return [] + + @property + @abstractmethod + def meansize(self) -> float: + """Mean size of the model, used for scaling visualization elements.""" + ... + + @abstractmethod + def add_arrow( + self, + start: np.ndarray | torch.Tensor, + end: np.ndarray | torch.Tensor, + color: tuple[float, float, float, float], + width: float = 0.015, + label: str | None = None, + ) -> None: + """Add an arrow from start to end position. + + Args: + start: Start position (3D vector). + end: End position (3D vector). + color: RGBA color (values 0-1). + width: Arrow shaft width. + label: Optional label for this arrow. + """ + ... + + @abstractmethod + def add_ghost_mesh( + self, + qpos: np.ndarray | torch.Tensor, + model: mujoco.MjModel, + mocap_pos: np.ndarray | torch.Tensor | None = None, + mocap_quat: np.ndarray | torch.Tensor | None = None, + alpha: float = 0.5, + label: str | None = None, + ) -> None: + """Add a ghost/transparent rendering of a robot at a target pose. + + Args: + qpos: Joint positions for the ghost pose. + model: MuJoCo model with pre-configured appearance (geom_rgba for colors). + mocap_pos: Optional mocap position(s) for fixed-base entities. + mocap_quat: Optional mocap quaternion(s) for fixed-base entities. + alpha: Transparency override (0=transparent, 1=opaque). May not be supported by + all implementations. + label: Optional label for this ghost. + """ + ... + + @abstractmethod + def add_frame( + self, + position: np.ndarray | torch.Tensor, + rotation_matrix: np.ndarray | torch.Tensor, + scale: float = 0.3, + label: str | None = None, + axis_radius: float = 0.01, + alpha: float = 1.0, + axis_colors: tuple[tuple[float, float, float], ...] | None = None, + ) -> None: + """Add a coordinate frame visualization. + + Args: + position: Position of the frame origin (3D vector). + rotation_matrix: Rotation matrix (3x3). + scale: Scale/length of the axis arrows. + label: Optional label for this frame. + axis_radius: Radius/thickness of the axis arrows. + alpha: Transparency override (0=transparent, 1=opaque). Note: The Viser + implementation does not support per-arrow transparency. All arrows in the + scene will share the same alpha value. + axis_colors: Optional tuple of 3 RGB colors for X, Y, Z axes. Each color is a + tuple of 3 floats (R, G, B) with values 0-1. If None, uses default RGB coloring + (X=red, Y=green, Z=blue). + """ + ... + + @abstractmethod + def add_sphere( + self, + center: np.ndarray | torch.Tensor, + radius: float, + color: tuple[float, float, float, float], + label: str | None = None, + ) -> None: + """Add a sphere visualization. + + Args: + center: Center position (3D vector). + radius: Sphere radius. + color: RGBA color (values 0-1). + label: Optional label for this sphere. + """ + ... + + @abstractmethod + def add_cylinder( + self, + start: np.ndarray | torch.Tensor, + end: np.ndarray | torch.Tensor, + radius: float, + color: tuple[float, float, float, float], + label: str | None = None, + ) -> None: + """Add a cylinder visualization. + + Args: + start: Bottom center position (3D vector). + end: Top center position (3D vector). + radius: Cylinder radius. + color: RGBA color (values 0-1). + label: Optional label for this cylinder. + """ + ... + + @abstractmethod + def clear(self) -> None: + """Clear all debug visualizations.""" + ... + + +class NullDebugVisualizer: + """No-op visualizer when visualization is disabled.""" + + def __init__(self, env_idx: int = 0, meansize: float = 0.1): + self.env_idx = env_idx + self.show_all_envs = False + self._meansize = meansize + + def get_env_indices(self, num_envs: int) -> Iterable[int]: + """Get the environment indices to visualize.""" + if self.show_all_envs: + return range(num_envs) + elif self.env_idx < num_envs: + return [self.env_idx] + else: + return [] + + @property + def meansize(self) -> float: + return self._meansize + + def add_arrow(self, start, end, color, width=0.015, label=None) -> None: + pass + + def add_ghost_mesh( + self, + qpos, + model, + mocap_pos=None, + mocap_quat=None, + alpha=0.5, + label=None, + ) -> None: + del mocap_pos, mocap_quat + pass + + def add_frame( + self, + position, + rotation_matrix, + scale=0.3, + label=None, + axis_radius=0.01, + alpha=1.0, + axis_colors=None, + ) -> None: + pass + + def add_sphere(self, center, radius, color, label=None) -> None: + pass + + def add_cylinder(self, start, end, radius, color, label=None) -> None: + pass + + def clear(self) -> None: + pass diff --git a/mjlab/src/mjlab/viewer/offscreen_renderer.py b/mjlab/src/mjlab/viewer/offscreen_renderer.py new file mode 100644 index 0000000000000000000000000000000000000000..094f20070fd7dbfcf5213687b41e4d1dd4a6fbe0 --- /dev/null +++ b/mjlab/src/mjlab/viewer/offscreen_renderer.py @@ -0,0 +1,167 @@ +"""MuJoCo offscreen renderer for headless visualization.""" + +from typing import Any, Callable + +import mujoco +import numpy as np + +from mjlab.scene import Scene +from mjlab.viewer.native.visualizer import MujocoNativeDebugVisualizer +from mjlab.viewer.viewer_config import ViewerConfig + +# Max number of envs to visualize (performance/memory limit). +# See FAQ: "How many environments can I visualize at once?" +_MAX_ENVS = 32 + + +class OffscreenRenderer: + def __init__(self, model: mujoco.MjModel, cfg: ViewerConfig, scene: Scene) -> None: + self._cfg = cfg + self._model = model + self._data = mujoco.MjData(model) + self._scene = scene + + self._model.vis.global_.offheight = cfg.height + self._model.vis.global_.offwidth = cfg.width + + if not cfg.enable_shadows: + self._model.light_castshadow[:] = False + if not cfg.enable_reflections: + self._model.mat_reflectance[:] = 0.0 + + self._cam = self._setup_camera() + + self._renderer: mujoco.Renderer | None = None + self._opt = mujoco.MjvOption() + self._pert = mujoco.MjvPerturb() + self._catmask = mujoco.mjtCatBit.mjCAT_DYNAMIC + + @property + def renderer(self) -> mujoco.Renderer: + if self._renderer is None: + raise ValueError("Renderer not initialized. Call 'initialize()' first.") + + return self._renderer + + def initialize(self) -> None: + if self._renderer is not None: + raise RuntimeError( + "Renderer is already initialized. Call 'close()' first to reinitialize." + ) + self._renderer = mujoco.Renderer( + model=self._model, height=self._cfg.height, width=self._cfg.width + ) + + def update( + self, + data: Any, + debug_vis_callback: Callable[[MujocoNativeDebugVisualizer], None] | None = None, + camera: str | None = None, + ) -> None: + """Update renderer with simulation data.""" + if self._renderer is None: + raise ValueError("Renderer not initialized. Call 'initialize()' first.") + + env_idx = self._cfg.env_idx + if self._model.nq > 0: + self._data.qpos[:] = data.qpos[env_idx].cpu().numpy() + self._data.qvel[:] = data.qvel[env_idx].cpu().numpy() + if self._model.nmocap > 0: + self._data.mocap_pos[:] = data.mocap_pos[env_idx].cpu().numpy() + self._data.mocap_quat[:] = data.mocap_quat[env_idx].cpu().numpy() + mujoco.mj_forward(self._model, self._data) + cam = camera if camera is not None else self._cam + self._renderer.update_scene(self._data, camera=cam) + + # Note: update_scene() resets the scene each frame, so no need to manually clear. + if debug_vis_callback is not None: + visualizer = MujocoNativeDebugVisualizer( + self._renderer.scene, self._model, env_idx=self._cfg.env_idx + ) + debug_vis_callback(visualizer) + + # Add additional environments as geoms. + nworld = data.nworld + for i in range(min(nworld, _MAX_ENVS)): + if self._model.nq > 0: + self._data.qpos[:] = data.qpos[i].cpu().numpy() + self._data.qvel[:] = data.qvel[i].cpu().numpy() + if self._model.nmocap > 0: + self._data.mocap_pos[:] = data.mocap_pos[i].cpu().numpy() + self._data.mocap_quat[:] = data.mocap_quat[i].cpu().numpy() + mujoco.mj_forward(self._model, self._data) + mujoco.mjv_addGeoms( + self._model, + self._data, + self._opt, + self._pert, + self._catmask.value, + self._renderer.scene, + ) + + def render(self) -> np.ndarray: + if self._renderer is None: + raise ValueError("Renderer not initialized. Call 'initialize()' first.") + + return self._renderer.render() + + def _setup_camera(self) -> mujoco.MjvCamera: + """Setup camera based on config's origin_type.""" + camera = mujoco.MjvCamera() + mujoco.mjv_defaultFreeCamera(self._model, camera) + + if self._cfg.origin_type == self._cfg.OriginType.WORLD: + # Free camera, no tracking. + camera.type = mujoco.mjtCamera.mjCAMERA_FREE.value + camera.fixedcamid = -1 + camera.trackbodyid = -1 + + elif self._cfg.origin_type == self._cfg.OriginType.ASSET_ROOT: + from mjlab.entity import Entity + + if self._cfg.entity_name: + robot: Entity = self._scene[self._cfg.entity_name] + else: + # Auto-detect if only one entity. + if len(self._scene.entities) == 1: + robot = list(self._scene.entities.values())[0] + else: + raise ValueError( + f"Multiple entities in scene ({len(self._scene.entities)}). " + "Specify entity_name to choose which one." + ) + + body_id = robot.indexing.root_body_id + camera.type = mujoco.mjtCamera.mjCAMERA_TRACKING.value + camera.trackbodyid = body_id + camera.fixedcamid = -1 + + elif self._cfg.origin_type == self._cfg.OriginType.ASSET_BODY: + if not self._cfg.entity_name or not self._cfg.body_name: + raise ValueError("entity_name/body_name required for ASSET_BODY origin type") + + from mjlab.entity import Entity + + robot: Entity = self._scene[self._cfg.entity_name] + if self._cfg.body_name not in robot.body_names: + raise ValueError( + f"Body '{self._cfg.body_name}' not found in asset '{self._cfg.entity_name}'" + ) + body_id_list, _ = robot.find_bodies(self._cfg.body_name) + body_id = robot.indexing.bodies[body_id_list[0]].id + + camera.type = mujoco.mjtCamera.mjCAMERA_TRACKING.value + camera.trackbodyid = body_id + camera.fixedcamid = -1 + + camera.lookat[:] = self._cfg.lookat + camera.elevation = self._cfg.elevation + camera.azimuth = self._cfg.azimuth + camera.distance = self._cfg.distance + + return camera + + def close(self) -> None: + if self._renderer is not None: + self._renderer.close() + self._renderer = None diff --git a/mjlab/src/mjlab/viewer/viewer_config.py b/mjlab/src/mjlab/viewer/viewer_config.py new file mode 100644 index 0000000000000000000000000000000000000000..ef3aef481779cd4594e4d043b5e5cbe5d9fb756c --- /dev/null +++ b/mjlab/src/mjlab/viewer/viewer_config.py @@ -0,0 +1,29 @@ +import enum +from dataclasses import dataclass + + +@dataclass +class ViewerConfig: + lookat: tuple[float, float, float] = (0.0, 0.0, 0.0) + distance: float = 5.0 + elevation: float = -45.0 + azimuth: float = 90.0 + + class OriginType(enum.Enum): + """The frame in which the camera position and target are defined.""" + + WORLD = enum.auto() + """The origin of the world.""" + ASSET_ROOT = enum.auto() + """The center of the asset defined by entity_name.""" + ASSET_BODY = enum.auto() + """The center of the body defined by body_name in asset defined by entity_name.""" + + origin_type: OriginType = OriginType.WORLD + entity_name: str | None = None + body_name: str | None = None + env_idx: int = 0 + enable_reflections: bool = True + enable_shadows: bool = True + height: int = 240 + width: int = 320