diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index a3b133fa1147..ef2baaf367ba 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.2.3" +version = "0.3.0" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index c7367f9efad6..8bad71e5eb0c 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,36 @@ Changelog --------- +0.3.0 (2026-02-25) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :mod:`isaaclab_newton.test.mock_interfaces` test infrastructure module with + structured mock views, factory functions, and unit tests — mirroring the + ``isaaclab_physx`` mock interface pattern: + + * :class:`~isaaclab_newton.test.mock_interfaces.views.MockNewtonArticulationView`: + extracted from monolithic ``mock_newton.py`` into its own module with lazy + initialization, individual ``set_mock_*`` methods, ``_noop_setters`` flag, + and numpy-based ``set_random_mock_data()``. + + * Factory functions: ``create_mock_articulation_view()``, + ``create_mock_quadruped_view()``, ``create_mock_humanoid_view()`` for + convenient test setup. + +* Added unit tests for mock interfaces: + ``test_mock_articulation_view.py`` and ``test_factories.py``. + +Changed +^^^^^^^ + +* Restructured ``mock_newton.py``: moved ``MockNewtonArticulationView`` to + ``views/mock_articulation_view.py`` and removed ``torch`` dependency from + the mock module (replaced with ``numpy`` for random data generation). + + 0.2.3 (2026-02-27) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/isaaclab_newton/test/__init__.py b/source/isaaclab_newton/isaaclab_newton/test/__init__.py new file mode 100644 index 000000000000..460a30569089 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/__init__.py b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/__init__.py new file mode 100644 index 000000000000..bc4409447df3 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/__init__.py @@ -0,0 +1,37 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Mock interfaces for Newton simulation views. + +This module provides mock implementations of Newton simulation components for unit testing +without requiring an actual simulation environment. +""" + +from .factories import ( + create_mock_articulation_view, + create_mock_humanoid_view, + create_mock_quadruped_view, +) +from .mock_newton import ( + MockNewtonContactSensor, + MockNewtonModel, + MockWrenchComposer, + create_mock_newton_manager, +) +from .views import MockNewtonArticulationView + +__all__ = [ + # Views + "MockNewtonArticulationView", + # Other mocks + "MockNewtonModel", + "MockWrenchComposer", + "MockNewtonContactSensor", + # Factory functions + "create_mock_articulation_view", + "create_mock_quadruped_view", + "create_mock_humanoid_view", + "create_mock_newton_manager", +] diff --git a/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/factories.py b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/factories.py new file mode 100644 index 000000000000..9a188456a8a7 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/factories.py @@ -0,0 +1,191 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Factory functions for creating mock Newton views.""" + +from __future__ import annotations + +from .views import MockNewtonArticulationView + + +def create_mock_articulation_view( + count: int = 1, + num_joints: int = 1, + num_bodies: int = 2, + joint_names: list[str] | None = None, + body_names: list[str] | None = None, + is_fixed_base: bool = False, + device: str = "cpu", +) -> MockNewtonArticulationView: + """Create a mock Newton articulation view. + + Args: + count: Number of articulation instances. + num_joints: Number of degrees of freedom (joints). + num_bodies: Number of bodies (links). + joint_names: Names of the joints. Defaults to auto-generated names. + body_names: Names of the bodies. Defaults to auto-generated names. + is_fixed_base: Whether the articulation has a fixed base. + device: Device for array allocation. + + Returns: + A MockNewtonArticulationView instance. + """ + return MockNewtonArticulationView( + num_instances=count, + num_bodies=num_bodies, + num_joints=num_joints, + device=device, + is_fixed_base=is_fixed_base, + joint_names=joint_names, + body_names=body_names, + ) + + +# -- Pre-configured factories -- + + +def create_mock_quadruped_view( + count: int = 1, + device: str = "cpu", +) -> MockNewtonArticulationView: + """Create a mock articulation view configured for a quadruped robot. + + Configuration: + - 12 DOFs (3 per leg x 4 legs: hip, thigh, calf) + - 13 links (base + 3 per leg) + - Floating base + + Args: + count: Number of articulation instances. + device: Device for array allocation. + + Returns: + A MockNewtonArticulationView configured for quadruped. + """ + joint_names = [ + "FL_hip_joint", + "FL_thigh_joint", + "FL_calf_joint", + "FR_hip_joint", + "FR_thigh_joint", + "FR_calf_joint", + "RL_hip_joint", + "RL_thigh_joint", + "RL_calf_joint", + "RR_hip_joint", + "RR_thigh_joint", + "RR_calf_joint", + ] + body_names = [ + "base", + "FL_hip", + "FL_thigh", + "FL_calf", + "FR_hip", + "FR_thigh", + "FR_calf", + "RL_hip", + "RL_thigh", + "RL_calf", + "RR_hip", + "RR_thigh", + "RR_calf", + ] + return MockNewtonArticulationView( + num_instances=count, + num_bodies=13, + num_joints=12, + device=device, + is_fixed_base=False, + joint_names=joint_names, + body_names=body_names, + ) + + +def create_mock_humanoid_view( + count: int = 1, + device: str = "cpu", +) -> MockNewtonArticulationView: + """Create a mock articulation view configured for a humanoid robot. + + Configuration: + - 21 DOFs (typical humanoid configuration) + - 22 links + - Floating base + + Args: + count: Number of articulation instances. + device: Device for array allocation. + + Returns: + A MockNewtonArticulationView configured for humanoid. + """ + joint_names = [ + # Torso + "torso_joint", + # Left arm + "left_shoulder_pitch", + "left_shoulder_roll", + "left_shoulder_yaw", + "left_elbow", + # Right arm + "right_shoulder_pitch", + "right_shoulder_roll", + "right_shoulder_yaw", + "right_elbow", + # Left leg + "left_hip_yaw", + "left_hip_roll", + "left_hip_pitch", + "left_knee", + "left_ankle_pitch", + "left_ankle_roll", + # Right leg + "right_hip_yaw", + "right_hip_roll", + "right_hip_pitch", + "right_knee", + "right_ankle_pitch", + "right_ankle_roll", + ] + body_names = [ + "pelvis", + "torso", + # Left arm + "left_shoulder", + "left_upper_arm", + "left_lower_arm", + "left_hand", + # Right arm + "right_shoulder", + "right_upper_arm", + "right_lower_arm", + "right_hand", + # Left leg + "left_hip", + "left_upper_leg", + "left_lower_leg", + "left_ankle", + "left_foot", + # Right leg + "right_hip", + "right_upper_leg", + "right_lower_leg", + "right_ankle", + "right_foot", + # Head + "neck", + "head", + ] + return MockNewtonArticulationView( + num_instances=count, + num_bodies=22, + num_joints=21, + device=device, + is_fixed_base=False, + joint_names=joint_names, + body_names=body_names, + ) diff --git a/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/mock_newton.py b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/mock_newton.py new file mode 100644 index 000000000000..a5fcacb8dab2 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/mock_newton.py @@ -0,0 +1,182 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Shared mock interfaces for testing and benchmarking Newton-based asset classes. + +This module provides mock implementations of Newton simulation components that can +be used to test ArticulationData, RigidObjectData, and related classes without +requiring an actual simulation environment. +""" + +from __future__ import annotations + +from unittest.mock import MagicMock, patch + +import warp as wp + + +class MockNewtonModel: + """Mock Newton model that provides gravity.""" + + def __init__(self, gravity: tuple[float, float, float] = (0.0, 0.0, -9.81), device: str = "cpu"): + self._gravity = wp.array([gravity], dtype=wp.vec3f, device=device) + + @property + def gravity(self): + return self._gravity + + +class MockWrenchComposer: + """Mock WrenchComposer for testing without full simulation infrastructure. + + This class mimics the interface of :class:`isaaclab.utils.wrench_composer.WrenchComposer` + and can be used to test Articulation and RigidObject classes. + """ + + def __init__(self, asset): + """Initialize the mock wrench composer. + + Args: + asset: The asset (Articulation or RigidObject) to compose wrenches for. + """ + self.num_envs = asset.num_instances + self.num_bodies = asset.num_bodies + self.device = asset.device + self._active = False + + # Create buffers matching the real WrenchComposer + self._composed_force_b = wp.zeros((self.num_envs, self.num_bodies), dtype=wp.vec3f, device=self.device) + self._composed_torque_b = wp.zeros((self.num_envs, self.num_bodies), dtype=wp.vec3f, device=self.device) + self._ALL_ENV_MASK_WP = wp.ones((self.num_envs,), dtype=wp.bool, device=self.device) + self._ALL_BODY_MASK_WP = wp.ones((self.num_bodies,), dtype=wp.bool, device=self.device) + + @property + def active(self) -> bool: + """Whether the wrench composer is active.""" + return self._active + + @property + def composed_force(self) -> wp.array: + """Composed force at the body's com frame.""" + return self._composed_force_b + + @property + def composed_torque(self) -> wp.array: + """Composed torque at the body's com frame.""" + return self._composed_torque_b + + def set_forces_and_torques( + self, + forces=None, + torques=None, + positions=None, + body_ids=None, + env_ids=None, + body_mask=None, + env_mask=None, + is_global: bool = False, + ): + """Mock set_forces_and_torques - just marks as active.""" + self._active = True + + def add_forces_and_torques( + self, + forces=None, + torques=None, + positions=None, + body_ids=None, + env_ids=None, + body_mask=None, + env_mask=None, + is_global: bool = False, + ): + """Mock add_forces_and_torques - just marks as active.""" + self._active = True + + def reset(self, env_ids=None, env_mask=None): + """Reset the composed force and torque.""" + self._composed_force_b.zero_() + self._composed_torque_b.zero_() + self._active = False + + +def create_mock_newton_manager( + patch_path: str, + gravity: tuple[float, float, float] = (0.0, 0.0, -9.81), +): + """Create a mock NewtonManager for testing. + + Args: + patch_path: The module path to patch + (e.g., "isaaclab_newton.assets.articulation.articulation_data.NewtonManager"). + gravity: Gravity vector to use for the mock model. + + Returns: + A context manager that patches the NewtonManager. + """ + mock_model = MockNewtonModel(gravity) + mock_state = MagicMock() + mock_control = MagicMock() + + return patch( + patch_path, + **{ + "get_model.return_value": mock_model, + "get_state_0.return_value": mock_state, + "get_control.return_value": mock_control, + "get_dt.return_value": 0.01, + }, + ) + + +class MockNewtonContactSensor: + """Mock Newton contact sensor for testing without full simulation infrastructure. + + This class mimics the interface of Newton's SensorContact and can be used to test + ContactSensor classes without requiring an actual simulation environment. + """ + + def __init__( + self, + num_sensing_objs: int, + num_counterparts: int = 1, + device: str = "cuda:0", + ): + """Initialize the mock contact sensor. + + Args: + num_sensing_objs: Number of sensing objects (e.g., bodies or shapes). + num_counterparts: Number of counterparts per sensing object. + device: Device to use. + """ + self.device = device + self.shape: tuple[int, int] = (num_sensing_objs, num_counterparts) + self.sensing_objs: list[tuple[int, int]] = [(i, 1) for i in range(num_sensing_objs)] + self.counterparts: list[tuple[int, int]] = [(i, 1) for i in range(num_counterparts)] + self.reading_indices: list[list[int]] = [list(range(num_counterparts)) for _ in range(num_sensing_objs)] + + # Net force array (n_sensing_objs, n_counterparts) of vec3 + self._net_force = wp.zeros(num_sensing_objs * num_counterparts, dtype=wp.vec3, device=device) + self.net_force = self._net_force.reshape(self.shape) + + def eval(self, contacts): + """Mock eval - does nothing since forces are set directly via set_mock_data.""" + pass + + def get_total_force(self) -> wp.array: + """Get the total net force measured by the contact sensor.""" + return self.net_force + + def set_mock_data(self, net_force: wp.array | None = None): + """Set mock contact force data. + + Args: + net_force: Force data shaped (num_sensing_objs, num_counterparts) of vec3. + If None, zeros the force data. + """ + if net_force is None: + self._net_force.zero_() + else: + self._net_force.assign(net_force) diff --git a/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/__init__.py b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/__init__.py new file mode 100644 index 000000000000..ca4ed19d1514 --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/__init__.py @@ -0,0 +1,12 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Mock Newton views.""" + +from .mock_articulation_view import MockNewtonArticulationView + +__all__ = [ + "MockNewtonArticulationView", +] diff --git a/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/mock_articulation_view.py b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/mock_articulation_view.py new file mode 100644 index 000000000000..1064eca3e4fa --- /dev/null +++ b/source/isaaclab_newton/isaaclab_newton/test/mock_interfaces/views/mock_articulation_view.py @@ -0,0 +1,507 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Mock implementation of Newton ArticulationView using structured Warp types.""" + +from __future__ import annotations + +import numpy as np +import warp as wp + + +class MockNewtonArticulationView: + """Mock Newton ArticulationView for unit testing without simulation. + + This class mimics the interface that ``ArticulationData`` and ``RigidObjectData`` + expect from Newton's selection API. It can be used for both articulation and + rigid object testing since Newton has no separate rigid body view. + + Data Shapes (structured Warp types with ``(N, 1, ...)`` convention): + - root_transforms: ``(N, 1)`` dtype=wp.transformf for floating base, + ``(N, 1, 1)`` for fixed base + - root_velocities: ``(N, 1)`` dtype=wp.spatial_vectorf (None for fixed base) + - link_transforms: ``(N, 1, L)`` dtype=wp.transformf + - link_velocities: ``(N, 1, L)`` dtype=wp.spatial_vectorf (None for fixed base) + - dof_positions: ``(N, 1, J)`` dtype=wp.float32 + - dof_velocities: ``(N, 1, J)`` dtype=wp.float32 + - body_com: ``(N, 1, L)`` dtype=wp.vec3f + - body_mass: ``(N, 1, L)`` dtype=wp.float32 + - body_inertia: ``(N, 1, L)`` dtype=wp.mat33f + + Where N = count, L = link_count, J = joint_dof_count + + Note: + Newton's selection API uses structured Warp types (``wp.transformf``, + ``wp.spatial_vectorf``, ``wp.vec3f``, ``wp.mat33f``) natively, unlike PhysX + which uses flat float32 arrays. + """ + + def __init__( + self, + num_instances: int = 1, + num_bodies: int = 2, + num_joints: int = 1, + device: str = "cpu", + is_fixed_base: bool = False, + joint_names: list[str] | None = None, + body_names: list[str] | None = None, + ): + """Initialize the mock Newton articulation view. + + Args: + num_instances: Number of articulation instances. + num_bodies: Number of bodies (links). + num_joints: Number of joints (DOFs). + device: Device for array allocation ("cpu" or "cuda:N"). + is_fixed_base: Whether the articulation has a fixed base. + joint_names: Names of joints. Defaults to ["joint_0", ...]. + body_names: Names of bodies. Defaults to ["body_0", ...]. + """ + self._count = num_instances + self._link_count = num_bodies + self._joint_dof_count = num_joints + self._device = device + self._is_fixed_base = is_fixed_base + self._noop_setters = False + + # Set joint and body names + self._joint_dof_names = joint_names if joint_names is not None else [f"joint_{i}" for i in range(num_joints)] + self._body_names = body_names if body_names is not None else [f"body_{i}" for i in range(num_bodies)] + + # Internal state (lazily initialized) + self._root_transforms: wp.array | None = None + self._root_velocities: wp.array | None = None + self._link_transforms: wp.array | None = None + self._link_velocities: wp.array | None = None + self._dof_positions: wp.array | None = None + self._dof_velocities: wp.array | None = None + + # Attributes dict (lazily initialized) + self._attributes: dict[str, wp.array | None] = { + "body_com": None, + "body_mass": None, + "body_inertia": None, + "joint_limit_lower": None, + "joint_limit_upper": None, + "joint_target_ke": None, + "joint_target_kd": None, + "joint_armature": None, + "joint_friction": None, + "joint_velocity_limit": None, + "joint_effort_limit": None, + "body_f": None, + "joint_f": None, + "joint_target_pos": None, + "joint_target_vel": None, + "joint_limit_ke": None, + "joint_limit_kd": None, + } + + # -- Properties -- + + @property + def count(self) -> int: + """Number of articulation instances.""" + return self._count + + @property + def link_count(self) -> int: + """Number of links (bodies) per instance.""" + return self._link_count + + @property + def joint_dof_count(self) -> int: + """Number of DOFs (joints) per instance.""" + return self._joint_dof_count + + @property + def is_fixed_base(self) -> bool: + """Whether the articulation has a fixed base.""" + return self._is_fixed_base + + @property + def joint_dof_names(self) -> list[str]: + """Names of the DOFs.""" + return self._joint_dof_names + + @property + def body_names(self) -> list[str]: + """Names of the bodies.""" + return self._body_names + + # -- Lazy Initialization Helpers -- + + def _ensure_root_transforms(self) -> wp.array: + """Lazily create root transforms with identity quaternions.""" + if self._root_transforms is None: + if self._is_fixed_base: + self._root_transforms = wp.zeros((self._count, 1, 1), dtype=wp.transformf, device=self._device) + else: + self._root_transforms = wp.zeros((self._count, 1), dtype=wp.transformf, device=self._device) + return self._root_transforms + + def _ensure_root_velocities(self) -> wp.array | None: + """Lazily create root velocities (None for fixed base).""" + if self._is_fixed_base: + return None + if self._root_velocities is None: + self._root_velocities = wp.zeros((self._count, 1), dtype=wp.spatial_vectorf, device=self._device) + return self._root_velocities + + def _ensure_link_transforms(self) -> wp.array: + """Lazily create link transforms.""" + if self._link_transforms is None: + self._link_transforms = wp.zeros( + (self._count, 1, self._link_count), dtype=wp.transformf, device=self._device + ) + return self._link_transforms + + def _ensure_link_velocities(self) -> wp.array | None: + """Lazily create link velocities (None for fixed base).""" + if self._is_fixed_base: + return None + if self._link_velocities is None: + self._link_velocities = wp.zeros( + (self._count, 1, self._link_count), dtype=wp.spatial_vectorf, device=self._device + ) + return self._link_velocities + + def _ensure_dof_positions(self) -> wp.array: + """Lazily create DOF positions.""" + if self._dof_positions is None: + self._dof_positions = wp.zeros( + (self._count, 1, self._joint_dof_count), dtype=wp.float32, device=self._device + ) + return self._dof_positions + + def _ensure_dof_velocities(self) -> wp.array: + """Lazily create DOF velocities.""" + if self._dof_velocities is None: + self._dof_velocities = wp.zeros( + (self._count, 1, self._joint_dof_count), dtype=wp.float32, device=self._device + ) + return self._dof_velocities + + def _ensure_attribute(self, name: str) -> wp.array: + """Lazily create an attribute array.""" + if self._attributes[name] is None: + self._attributes[name] = self._create_default_attribute(name) + return self._attributes[name] + + def _create_default_attribute(self, name: str) -> wp.array: + """Create a default attribute array based on name.""" + N, L, J = self._count, self._link_count, self._joint_dof_count + dev = self._device + + if name == "body_com": + return wp.zeros((N, 1, L), dtype=wp.vec3f, device=dev) + elif name == "body_mass": + return wp.zeros((N, 1, L), dtype=wp.float32, device=dev) + elif name == "body_inertia": + return wp.zeros((N, 1, L), dtype=wp.mat33f, device=dev) + elif name == "body_f": + return wp.zeros((N, 1, L), dtype=wp.spatial_vectorf, device=dev) + elif name in ( + "joint_limit_lower", + "joint_limit_upper", + "joint_target_ke", + "joint_target_kd", + "joint_armature", + "joint_friction", + "joint_velocity_limit", + "joint_effort_limit", + "joint_f", + "joint_target_pos", + "joint_target_vel", + "joint_limit_ke", + "joint_limit_kd", + ): + return wp.zeros((N, 1, J), dtype=wp.float32, device=dev) + else: + raise KeyError(f"Unknown attribute: {name}") + + # -- Root Getters -- + + def get_root_transforms(self, state) -> wp.array: + """Get world transforms of root links. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array with dtype=wp.transformf. Shape ``(N, 1)`` for floating base, + ``(N, 1, 1)`` for fixed base. + """ + return self._ensure_root_transforms() + + def get_root_velocities(self, state) -> wp.array | None: + """Get velocities of root links. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array of shape ``(N, 1)`` with dtype=wp.spatial_vectorf, + or None for fixed base. + """ + return self._ensure_root_velocities() + + # -- Link Getters -- + + def get_link_transforms(self, state) -> wp.array: + """Get world transforms of all links. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array of shape ``(N, 1, L)`` with dtype=wp.transformf. + """ + return self._ensure_link_transforms() + + def get_link_velocities(self, state) -> wp.array | None: + """Get velocities of all links. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array of shape ``(N, 1, L)`` with dtype=wp.spatial_vectorf, + or None for fixed base. + """ + return self._ensure_link_velocities() + + # -- DOF Getters -- + + def get_dof_positions(self, state) -> wp.array: + """Get positions of all DOFs. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array of shape ``(N, 1, J)`` with dtype=wp.float32. + """ + return self._ensure_dof_positions() + + def get_dof_velocities(self, state) -> wp.array: + """Get velocities of all DOFs. + + Args: + state: Newton state object (unused in mock). + + Returns: + Warp array of shape ``(N, 1, J)`` with dtype=wp.float32. + """ + return self._ensure_dof_velocities() + + # -- Attribute Getter -- + + def get_attribute(self, name: str, model_or_state) -> wp.array: + """Get a named attribute array. + + Args: + name: Attribute name (e.g. "body_mass", "joint_target_ke"). + model_or_state: Newton model or state object (unused in mock). + + Returns: + Warp array for the requested attribute. + + Raises: + KeyError: If the attribute name is unknown. + """ + return self._ensure_attribute(name) + + # -- Root Setters -- + + def set_root_transforms(self, state, transforms: wp.array) -> None: + """Set world transforms of root links. + + Args: + state: Newton state object (unused in mock). + transforms: Warp array with dtype=wp.transformf matching root shape. + + Raises: + ValueError: If the transforms shape does not match the expected root shape. + """ + if self._noop_setters: + return + expected = self._ensure_root_transforms() + if transforms.shape != expected.shape: + raise ValueError(f"Root transforms shape mismatch: expected {expected.shape}, got {transforms.shape}") + expected.assign(transforms) + + def set_root_velocities(self, state, velocities: wp.array) -> None: + """Set velocities of root links. + + Args: + state: Newton state object (unused in mock). + velocities: Warp array of shape ``(N, 1)`` with dtype=wp.spatial_vectorf. + """ + if self._noop_setters: + return + vel = self._ensure_root_velocities() + if vel is not None: + vel.assign(velocities) + + # -- Mock Setters (direct test data injection) -- + + def set_mock_root_transforms(self, transforms: wp.array) -> None: + """Set mock root transform data directly for testing. + + Args: + transforms: Warp array with dtype=wp.transformf. + """ + self._root_transforms = transforms + + def set_mock_root_velocities(self, velocities: wp.array) -> None: + """Set mock root velocity data directly for testing. + + Args: + velocities: Warp array with dtype=wp.spatial_vectorf. + """ + self._root_velocities = velocities + + def set_mock_link_transforms(self, transforms: wp.array) -> None: + """Set mock link transform data directly for testing. + + Args: + transforms: Warp array of shape ``(N, 1, L)`` with dtype=wp.transformf. + """ + self._link_transforms = transforms + + def set_mock_link_velocities(self, velocities: wp.array) -> None: + """Set mock link velocity data directly for testing. + + Args: + velocities: Warp array of shape ``(N, 1, L)`` with dtype=wp.spatial_vectorf. + """ + self._link_velocities = velocities + + def set_mock_dof_positions(self, positions: wp.array) -> None: + """Set mock DOF position data directly for testing. + + Args: + positions: Warp array of shape ``(N, 1, J)`` with dtype=wp.float32. + """ + self._dof_positions = positions + + def set_mock_dof_velocities(self, velocities: wp.array) -> None: + """Set mock DOF velocity data directly for testing. + + Args: + velocities: Warp array of shape ``(N, 1, J)`` with dtype=wp.float32. + """ + self._dof_velocities = velocities + + def set_mock_masses(self, masses: wp.array) -> None: + """Set mock body mass data directly for testing. + + Args: + masses: Warp array of shape ``(N, 1, L)`` with dtype=wp.float32. + """ + self._attributes["body_mass"] = masses + + def set_mock_coms(self, coms: wp.array) -> None: + """Set mock body center-of-mass data directly for testing. + + Args: + coms: Warp array of shape ``(N, 1, L)`` with dtype=wp.vec3f. + """ + self._attributes["body_com"] = coms + + def set_mock_inertias(self, inertias: wp.array) -> None: + """Set mock body inertia data directly for testing. + + Args: + inertias: Warp array of shape ``(N, 1, L)`` with dtype=wp.mat33f. + """ + self._attributes["body_inertia"] = inertias + + # -- Benchmark Utilities -- + + def set_random_mock_data(self) -> None: + """Set all internal state to random values for benchmarking. + + Uses numpy for random data generation (matching PhysX mock pattern). + """ + N = self._count + L = self._link_count + J = self._joint_dof_count + dev = self._device + + # Root transforms + if self._is_fixed_base: + root_tf_np = np.random.randn(N, 1, 1, 7).astype(np.float32) + root_tf_np[..., 3:7] /= np.linalg.norm(root_tf_np[..., 3:7], axis=-1, keepdims=True) + self._root_transforms = wp.array(root_tf_np, dtype=wp.transformf, device=dev) + else: + root_tf_np = np.random.randn(N, 1, 7).astype(np.float32) + root_tf_np[..., 3:7] /= np.linalg.norm(root_tf_np[..., 3:7], axis=-1, keepdims=True) + self._root_transforms = wp.array(root_tf_np, dtype=wp.transformf, device=dev) + + # Root velocities (floating base only) + root_vel_np = np.random.randn(N, 1, 6).astype(np.float32) + self._root_velocities = wp.array(root_vel_np, dtype=wp.spatial_vectorf, device=dev) + + # Link transforms + link_tf_np = np.random.randn(N, 1, L, 7).astype(np.float32) + link_tf_np[..., 3:7] /= np.linalg.norm(link_tf_np[..., 3:7], axis=-1, keepdims=True) + self._link_transforms = wp.array(link_tf_np, dtype=wp.transformf, device=dev) + + # Link velocities (floating base only) + if not self._is_fixed_base: + link_vel_np = np.random.randn(N, 1, L, 6).astype(np.float32) + self._link_velocities = wp.array(link_vel_np, dtype=wp.spatial_vectorf, device=dev) + + # DOF state + self._dof_positions = wp.array(np.random.randn(N, 1, J).astype(np.float32), dtype=wp.float32, device=dev) + self._dof_velocities = wp.array(np.random.randn(N, 1, J).astype(np.float32), dtype=wp.float32, device=dev) + + # Body properties + self._attributes["body_com"] = wp.array( + np.random.randn(N, 1, L, 3).astype(np.float32), + dtype=wp.vec3f, + device=dev, + ) + self._attributes["body_mass"] = wp.array( + (np.random.rand(N, 1, L) * 10 + 0.1).astype(np.float32), + dtype=wp.float32, + device=dev, + ) + self._attributes["body_inertia"] = wp.array( + np.random.randn(N, 1, L, 9).astype(np.float32), + dtype=wp.mat33f, + device=dev, + ) + + # Joint properties + for attr_name in ( + "joint_limit_lower", + "joint_limit_upper", + "joint_target_ke", + "joint_target_kd", + "joint_armature", + "joint_friction", + "joint_velocity_limit", + "joint_effort_limit", + "joint_f", + "joint_target_pos", + "joint_target_vel", + "joint_limit_ke", + "joint_limit_kd", + ): + self._attributes[attr_name] = wp.array( + np.random.randn(N, 1, J).astype(np.float32), + dtype=wp.float32, + device=dev, + ) + + # Body forces + self._attributes["body_f"] = wp.array( + np.random.randn(N, 1, L, 6).astype(np.float32), + dtype=wp.spatial_vectorf, + device=dev, + ) diff --git a/source/isaaclab_newton/test/test_mock_interfaces/__init__.py b/source/isaaclab_newton/test/test_mock_interfaces/__init__.py new file mode 100644 index 000000000000..c704dd9c2ec3 --- /dev/null +++ b/source/isaaclab_newton/test/test_mock_interfaces/__init__.py @@ -0,0 +1,6 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for mock Newton interfaces.""" diff --git a/source/isaaclab_newton/test/test_mock_interfaces/test_factories.py b/source/isaaclab_newton/test/test_mock_interfaces/test_factories.py new file mode 100644 index 000000000000..5713fd1eff5c --- /dev/null +++ b/source/isaaclab_newton/test/test_mock_interfaces/test_factories.py @@ -0,0 +1,63 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for Newton mock factory functions.""" + +from isaaclab_newton.test.mock_interfaces.factories import ( + create_mock_articulation_view, + create_mock_humanoid_view, + create_mock_quadruped_view, +) +from isaaclab_newton.test.mock_interfaces.views import MockNewtonArticulationView + + +class TestFactories: + """Tests for Newton mock factory functions.""" + + def test_create_mock_articulation_view_basic(self): + """Test basic factory usage.""" + view = create_mock_articulation_view(count=4, num_joints=12, num_bodies=13) + assert view.count == 4 + assert view.joint_dof_count == 12 + assert view.link_count == 13 + assert isinstance(view, MockNewtonArticulationView) + + def test_create_mock_articulation_view_fixed_base(self): + """Test factory with fixed base flag.""" + view = create_mock_articulation_view(count=2, num_joints=6, num_bodies=7, is_fixed_base=True) + assert view.count == 2 + assert view.is_fixed_base is True + + def test_create_mock_articulation_view_custom_names(self): + """Test factory with custom names.""" + joint_names = ["j1", "j2"] + body_names = ["b1", "b2", "b3"] + view = create_mock_articulation_view( + count=1, num_joints=2, num_bodies=3, joint_names=joint_names, body_names=body_names + ) + assert view.joint_dof_names == joint_names + assert view.body_names == body_names + + def test_create_mock_quadruped_view(self): + """Test quadruped factory.""" + view = create_mock_quadruped_view(count=4) + assert view.count == 4 + assert view.joint_dof_count == 12 + assert view.link_count == 13 + assert view.is_fixed_base is False + assert "FL_hip_joint" in view.joint_dof_names + assert "base" in view.body_names + assert isinstance(view, MockNewtonArticulationView) + + def test_create_mock_humanoid_view(self): + """Test humanoid factory.""" + view = create_mock_humanoid_view(count=2) + assert view.count == 2 + assert view.joint_dof_count == 21 + assert view.link_count == 22 + assert view.is_fixed_base is False + assert "left_elbow" in view.joint_dof_names + assert "pelvis" in view.body_names + assert isinstance(view, MockNewtonArticulationView) diff --git a/source/isaaclab_newton/test/test_mock_interfaces/test_mock_articulation_view.py b/source/isaaclab_newton/test/test_mock_interfaces/test_mock_articulation_view.py new file mode 100644 index 000000000000..2f970323a63d --- /dev/null +++ b/source/isaaclab_newton/test/test_mock_interfaces/test_mock_articulation_view.py @@ -0,0 +1,383 @@ +# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Tests for MockNewtonArticulationView.""" + +import numpy as np +import pytest +import warp as wp +from isaaclab_newton.test.mock_interfaces.views import MockNewtonArticulationView + + +class TestMockNewtonArticulationViewInit: + """Tests for MockNewtonArticulationView initialization.""" + + def test_default_init(self): + """Test default initialization.""" + view = MockNewtonArticulationView() + assert view.count == 1 + assert view.joint_dof_count == 1 + assert view.link_count == 2 + assert view.is_fixed_base is False + + def test_custom_configuration(self): + """Test initialization with custom configuration.""" + view = MockNewtonArticulationView( + num_instances=4, + num_joints=12, + num_bodies=13, + is_fixed_base=True, + ) + assert view.count == 4 + assert view.joint_dof_count == 12 + assert view.link_count == 13 + assert view.is_fixed_base is True + + def test_custom_names(self): + """Test initialization with custom joint and body names.""" + joint_names = ["joint_0", "joint_1"] + body_names = ["base", "link_1", "link_2"] + view = MockNewtonArticulationView( + num_joints=2, + num_bodies=3, + joint_names=joint_names, + body_names=body_names, + ) + assert view.joint_dof_names == joint_names + assert view.body_names == body_names + + def test_fixed_base_config(self): + """Test fixed-base configuration.""" + view = MockNewtonArticulationView( + num_instances=2, + num_joints=6, + num_bodies=7, + is_fixed_base=True, + ) + assert view.is_fixed_base is True + # Root velocities should be None for fixed base + assert view.get_root_velocities(None) is None + assert view.get_link_velocities(None) is None + + +class TestMockNewtonArticulationViewRootGetters: + """Tests for MockNewtonArticulationView root getter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_get_root_transforms_shape(self, view): + """Test root transforms shape - should be (N, 1) with wp.transformf dtype.""" + transforms = view.get_root_transforms(None) + assert transforms.shape == (4, 1) + assert transforms.dtype == wp.transformf + + def test_get_root_transforms_default_identity(self, view): + """Test that default root transforms are zero-initialized.""" + transforms = view.get_root_transforms(None) + transforms_np = transforms.numpy() + # Default is zero, meaning all zeros for position and quaternion + np.testing.assert_allclose(transforms_np, 0.0) + + def test_get_root_velocities_shape(self, view): + """Test root velocities shape - should be (N, 1) with wp.spatial_vectorf dtype.""" + velocities = view.get_root_velocities(None) + assert velocities.shape == (4, 1) + assert velocities.dtype == wp.spatial_vectorf + + def test_fixed_base_root_velocities_none(self): + """Test that fixed-base root velocities are None.""" + view = MockNewtonArticulationView( + num_instances=4, num_joints=12, num_bodies=13, is_fixed_base=True, device="cpu" + ) + assert view.get_root_velocities(None) is None + + def test_fixed_base_root_transforms_shape(self): + """Test that fixed-base root transforms have shape (N, 1, 1).""" + view = MockNewtonArticulationView( + num_instances=4, num_joints=12, num_bodies=13, is_fixed_base=True, device="cpu" + ) + transforms = view.get_root_transforms(None) + assert transforms.shape == (4, 1, 1) + assert transforms.dtype == wp.transformf + + +class TestMockNewtonArticulationViewLinkGetters: + """Tests for MockNewtonArticulationView link getter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_get_link_transforms_shape(self, view): + """Test link transforms shape - should be (N, 1, L) with wp.transformf dtype.""" + transforms = view.get_link_transforms(None) + assert transforms.shape == (4, 1, 13) + assert transforms.dtype == wp.transformf + + def test_get_link_velocities_shape(self, view): + """Test link velocities shape - should be (N, 1, L) with wp.spatial_vectorf dtype.""" + velocities = view.get_link_velocities(None) + assert velocities.shape == (4, 1, 13) + assert velocities.dtype == wp.spatial_vectorf + + def test_fixed_base_link_velocities_none(self): + """Test that fixed-base link velocities are None.""" + view = MockNewtonArticulationView( + num_instances=4, num_joints=12, num_bodies=13, is_fixed_base=True, device="cpu" + ) + assert view.get_link_velocities(None) is None + + +class TestMockNewtonArticulationViewDOFGetters: + """Tests for MockNewtonArticulationView DOF getter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_get_dof_positions_shape(self, view): + """Test DOF positions shape - should be (N, 1, J).""" + positions = view.get_dof_positions(None) + assert positions.shape == (4, 1, 12) + assert positions.dtype == wp.float32 + + def test_get_dof_velocities_shape(self, view): + """Test DOF velocities shape - should be (N, 1, J).""" + velocities = view.get_dof_velocities(None) + assert velocities.shape == (4, 1, 12) + assert velocities.dtype == wp.float32 + + @pytest.mark.parametrize( + "attr_name", + [ + "joint_limit_lower", + "joint_limit_upper", + "joint_target_ke", + "joint_target_kd", + "joint_armature", + "joint_friction", + "joint_velocity_limit", + "joint_effort_limit", + ], + ) + def test_get_joint_attribute_shape(self, view, attr_name): + """Test joint attribute shapes via get_attribute().""" + attr = view.get_attribute(attr_name, None) + assert attr.shape == (4, 1, 12) + assert attr.dtype == wp.float32 + + +class TestMockNewtonArticulationViewMassGetters: + """Tests for MockNewtonArticulationView mass property getter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_get_body_mass_shape(self, view): + """Test body mass shape via get_attribute().""" + mass = view.get_attribute("body_mass", None) + assert mass.shape == (4, 1, 13) + assert mass.dtype == wp.float32 + + def test_get_body_com_shape(self, view): + """Test body COM shape via get_attribute().""" + com = view.get_attribute("body_com", None) + assert com.shape == (4, 1, 13) + assert com.dtype == wp.vec3f + + def test_get_body_inertia_shape(self, view): + """Test body inertia shape via get_attribute().""" + inertia = view.get_attribute("body_inertia", None) + assert inertia.shape == (4, 1, 13) + assert inertia.dtype == wp.mat33f + + +class TestMockNewtonArticulationViewSetters: + """Tests for MockNewtonArticulationView setter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_set_root_transforms(self, view): + """Test setting root transforms round-trip.""" + new_transforms = wp.zeros((4, 1), dtype=wp.transformf, device="cpu") + view.set_root_transforms(None, new_transforms) + result = view.get_root_transforms(None) + np.testing.assert_allclose(result.numpy(), new_transforms.numpy()) + + def test_set_root_velocities(self, view): + """Test setting root velocities round-trip.""" + new_velocities = wp.zeros((4, 1), dtype=wp.spatial_vectorf, device="cpu") + view.set_root_velocities(None, new_velocities) + result = view.get_root_velocities(None) + np.testing.assert_allclose(result.numpy(), new_velocities.numpy()) + + def test_noop_setters_flag(self, view): + """Test that _noop_setters disables writes.""" + # Set initial data + initial_transforms = wp.zeros((4, 1), dtype=wp.transformf, device="cpu") + view.set_root_transforms(None, initial_transforms) + + # Enable noop + view._noop_setters = True + + # Try to write different data + new_transforms = wp.ones((4, 1), dtype=wp.transformf, device="cpu") + view.set_root_transforms(None, new_transforms) + + # Should still have initial data + result = view.get_root_transforms(None) + np.testing.assert_allclose(result.numpy(), initial_transforms.numpy()) + + +class TestMockNewtonArticulationViewMockSetters: + """Tests for MockNewtonArticulationView mock setter methods.""" + + @pytest.fixture + def view(self): + """Create a view with 4 instances, 12 DOFs, 13 links.""" + return MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + + def test_set_mock_root_transforms(self, view): + """Test mock root transform setter round-trip.""" + mock_data = wp.zeros((4, 1), dtype=wp.transformf, device="cpu") + view.set_mock_root_transforms(mock_data) + result = view.get_root_transforms(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + def test_set_mock_root_velocities(self, view): + """Test mock root velocity setter round-trip.""" + mock_data = wp.zeros((4, 1), dtype=wp.spatial_vectorf, device="cpu") + view.set_mock_root_velocities(mock_data) + result = view.get_root_velocities(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + def test_set_mock_link_transforms(self, view): + """Test mock link transform setter round-trip.""" + mock_data = wp.zeros((4, 1, 13), dtype=wp.transformf, device="cpu") + view.set_mock_link_transforms(mock_data) + result = view.get_link_transforms(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + def test_set_mock_link_velocities(self, view): + """Test mock link velocity setter round-trip.""" + mock_data = wp.zeros((4, 1, 13), dtype=wp.spatial_vectorf, device="cpu") + view.set_mock_link_velocities(mock_data) + result = view.get_link_velocities(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + def test_set_mock_dof_positions(self, view): + """Test mock DOF position setter round-trip.""" + mock_data = wp.array(np.random.randn(4, 1, 12).astype(np.float32), dtype=wp.float32, device="cpu") + view.set_mock_dof_positions(mock_data) + result = view.get_dof_positions(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy(), rtol=1e-5) + + def test_set_mock_dof_velocities(self, view): + """Test mock DOF velocity setter round-trip.""" + mock_data = wp.array(np.random.randn(4, 1, 12).astype(np.float32), dtype=wp.float32, device="cpu") + view.set_mock_dof_velocities(mock_data) + result = view.get_dof_velocities(None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy(), rtol=1e-5) + + def test_set_mock_masses(self, view): + """Test mock body mass setter round-trip.""" + mock_data = wp.array((np.random.rand(4, 1, 13) * 10).astype(np.float32), dtype=wp.float32, device="cpu") + view.set_mock_masses(mock_data) + result = view.get_attribute("body_mass", None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy(), rtol=1e-5) + + def test_set_mock_coms(self, view): + """Test mock body COM setter round-trip.""" + mock_data = wp.zeros((4, 1, 13), dtype=wp.vec3f, device="cpu") + view.set_mock_coms(mock_data) + result = view.get_attribute("body_com", None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + def test_set_mock_inertias(self, view): + """Test mock body inertia setter round-trip.""" + mock_data = wp.zeros((4, 1, 13), dtype=wp.mat33f, device="cpu") + view.set_mock_inertias(mock_data) + result = view.get_attribute("body_inertia", None) + np.testing.assert_allclose(result.numpy(), mock_data.numpy()) + + +class TestMockNewtonArticulationViewRandomData: + """Tests for MockNewtonArticulationView random data generation.""" + + def test_set_random_mock_data_populates_arrays(self): + """Test that set_random_mock_data populates non-None arrays.""" + view = MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + view.set_random_mock_data() + + # Root state should be populated + transforms = view.get_root_transforms(None) + assert transforms is not None + assert transforms.shape == (4, 1) + + velocities = view.get_root_velocities(None) + assert velocities is not None + assert velocities.shape == (4, 1) + + # Link state should be populated + link_transforms = view.get_link_transforms(None) + assert link_transforms is not None + assert link_transforms.shape == (4, 1, 13) + + link_velocities = view.get_link_velocities(None) + assert link_velocities is not None + assert link_velocities.shape == (4, 1, 13) + + # DOF state should be populated + positions = view.get_dof_positions(None) + assert positions is not None + assert positions.shape == (4, 1, 12) + + velocities = view.get_dof_velocities(None) + assert velocities is not None + assert velocities.shape == (4, 1, 12) + + # Attributes should be populated + mass = view.get_attribute("body_mass", None) + assert mass is not None + assert mass.shape == (4, 1, 13) + + def test_set_random_mock_data_fixed_base(self): + """Test random data with fixed base (no velocities).""" + view = MockNewtonArticulationView( + num_instances=4, num_joints=12, num_bodies=13, is_fixed_base=True, device="cpu" + ) + view.set_random_mock_data() + + # Root transforms should have fixed-base shape + transforms = view.get_root_transforms(None) + assert transforms.shape == (4, 1, 1) + + # Velocities should still be None for fixed base + assert view.get_root_velocities(None) is None + assert view.get_link_velocities(None) is None + + def test_set_random_mock_data_has_nonzero_values(self): + """Test that random data has non-zero values.""" + view = MockNewtonArticulationView(num_instances=4, num_joints=12, num_bodies=13, device="cpu") + view.set_random_mock_data() + + positions = view.get_dof_positions(None) + assert not np.allclose(positions.numpy(), 0.0) + + def test_get_attribute_unknown_raises(self): + """Test that requesting an unknown attribute raises KeyError.""" + view = MockNewtonArticulationView() + with pytest.raises(KeyError): + view.get_attribute("nonexistent_attribute", None)