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

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 22 additions & 23 deletions source/isaaclab/isaaclab/scene/interactive_scene.py
Original file line number Diff line number Diff line change
Expand Up @@ -583,6 +583,11 @@ def _is_scene_setup_from_cfg(self) -> bool:

def _add_entities_from_cfg(self):
"""Add scene entities from the config."""

def resolve_env_ns(path: str, ns: str) -> str:
"""Normalize ``{ENV_REGEX_NS}`` (or a literal env-regex) and substitute *ns*."""
return path.replace(self.env_regex_ns, "{ENV_REGEX_NS}").format(ENV_REGEX_NS=ns)

# parse the entire scene config and resolve regex
for asset_name, asset_cfg in self.cfg.__dict__.items():
# skip keywords
Expand All @@ -595,11 +600,12 @@ def _add_entities_from_cfg(self):
# In order to compose cloner behavior more flexibly, we ask each spawner to spawn prototypes in
# prepared /World/template path, once all template is ready, cloner can determine what rules to follow
# to combine, and distribute the templates to cloned environments.
asset_cfg.prim_path = asset_cfg.prim_path.replace(self.env_regex_ns, "{ENV_REGEX_NS}")
destinations_regex_ns = asset_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns)
if self.env_regex_ns[:-2] in destinations_regex_ns:
# Sensors are excluded — they don't spawn prims and need env-regex
# paths during __init__ for cl_register_site.
destinations_regex_ns = resolve_env_ns(asset_cfg.prim_path, self.env_regex_ns)
if not isinstance(asset_cfg, SensorBaseCfg) and self.env_regex_ns[:-2] in destinations_regex_ns:
require_clone = True
prototype_root = asset_cfg.prim_path.format(ENV_REGEX_NS=self.cloner_cfg.template_root)
prototype_root = resolve_env_ns(asset_cfg.prim_path, self.cloner_cfg.template_root)
asset_cfg.prim_path = f"{prototype_root}/{self.cloner_cfg.template_prototype_identifier}_.*"
else:
asset_cfg.prim_path = destinations_regex_ns
Expand All @@ -615,29 +621,22 @@ def _add_entities_from_cfg(self):
self._rigid_objects[asset_name] = asset_cfg.class_type(asset_cfg)
elif isinstance(asset_cfg, SensorBaseCfg):
if isinstance(asset_cfg, ContactSensorCfg):
if asset_cfg.shape_path is not None:
updated_shape_names_expr = []
for filter_prim_path in asset_cfg.shape_path:
updated_shape_names_expr.append(filter_prim_path.format(ENV_REGEX_NS=self.env_regex_ns))
asset_cfg.shape_path = updated_shape_names_expr
if asset_cfg.filter_prim_paths_expr is not None:
updated_contact_partners_body_expr = []
for contact_partners_body_expr in asset_cfg.filter_prim_paths_expr:
updated_contact_partners_body_expr.append(
contact_partners_body_expr.format(ENV_REGEX_NS=self.env_regex_ns)
)
asset_cfg.filter_prim_paths_expr = updated_contact_partners_body_expr
if asset_cfg.filter_shape_paths_expr is not None:
updated_contact_partners_shape_expr = []
for contact_partners_shape_expr in asset_cfg.filter_shape_paths_expr:
updated_contact_partners_shape_expr.append(
contact_partners_shape_expr.format(ENV_REGEX_NS=self.env_regex_ns)
)
asset_cfg.filter_shape_paths_expr = updated_contact_partners_shape_expr
asset_cfg.filter_prim_paths_expr = [
resolve_env_ns(e, self.env_regex_ns) for e in asset_cfg.filter_prim_paths_expr
]
if hasattr(asset_cfg, "sensor_shape_prim_expr") and asset_cfg.sensor_shape_prim_expr is not None:
asset_cfg.sensor_shape_prim_expr = [
resolve_env_ns(e, self.env_regex_ns) for e in asset_cfg.sensor_shape_prim_expr
]
if hasattr(asset_cfg, "filter_shape_prim_expr") and asset_cfg.filter_shape_prim_expr is not None:
asset_cfg.filter_shape_prim_expr = [
resolve_env_ns(e, self.env_regex_ns) for e in asset_cfg.filter_shape_prim_expr
]
elif isinstance(asset_cfg, FrameTransformerCfg):
if asset_cfg.target_frames is not None:
for target_frame in asset_cfg.target_frames:
target_frame.prim_path = target_frame.prim_path.format(ENV_REGEX_NS=self.env_regex_ns)
target_frame.prim_path = resolve_env_ns(target_frame.prim_path, self.env_regex_ns)
self._sensors[asset_name] = asset_cfg.class_type(asset_cfg)
elif isinstance(asset_cfg, AssetBaseCfg):
# manually spawn asset
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ def reset(self, env_ids: Sequence[int] | None = None, env_mask: wp.array(dtype=w
env_mask: The masks of the environments to reset. Defaults to None: all the environments are reset.
"""
# reset the timers and counters
super().reset(env_ids)
super().reset(env_ids, env_mask)

@abstractmethod
def find_bodies(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,44 @@

@configclass
class ContactSensorCfg(SensorBaseCfg):
"""Configuration for the contact sensor."""
"""Configuration for the contact sensor.

Sensing bodies are selected via :attr:`SensorBaseCfg.prim_path`. Filter bodies for
per-partner force reporting are selected via :attr:`filter_prim_paths_expr`.

Only body-level sensing and filtering are supported. For shape-level granularity,
see ``NewtonContactSensorCfg`` in ``isaaclab_newton``.
"""

class_type: type = ContactSensor

track_pose: bool = False
"""Whether to track the pose of the sensor's origin. Defaults to False."""

track_contact_points: bool = False
"""Whether to track the contact point locations. Defaults to False."""

track_friction_forces: bool = False
"""Whether to track the friction forces at the contact points. Defaults to False."""

max_contact_data_count_per_prim: int | None = None
"""The maximum number of contacts across all batches of the sensor to keep track of. Default is 4, where supported.

This parameter sets the total maximum counts of the simulation across all bodies and environments. The total number
of contacts allowed is max_contact_data_count_per_prim*num_envs*num_sensor_bodies.

.. note::

If the environment is very contact rich it is suggested to increase this parameter to avoid out of bounds memory
errors and loss of contact data leading to inaccurate measurements.
"""

track_air_time: bool = False
"""Whether to track the air/contact time of the bodies (time between contacts). Defaults to False."""

force_threshold: float = 0.0
force_threshold: float | None = None
"""The threshold on the norm of the contact force that determines whether two bodies are in collision or not.
Defaults to None, in which case the sensor backend chooses an appropriate value.

This value is only used for tracking the mode duration (the time in contact or in air),
if :attr:`track_air_time` is True.
Expand All @@ -34,73 +60,26 @@ class ContactSensorCfg(SensorBaseCfg):
"""Number of past frames to store in the sensor buffers. Defaults to 0, which means that only
the current data is stored (no history)."""

shape_path: list[str] | None = None
"""A list of expressions to filter contacts shapes with. Defaults to None. If both :attr:`body_names_expr` and
:attr:`shape_names_expr` are None, the contact with all bodies/shapes is reported.

Only one of :attr:`body_names_expr` or :attr:`shape_names_expr` can be provided.
If both are provided, an error will be raised.

We make an explicit difference between a body and a shape. A body is a rigid body, while a shape is a collision
shape. A body can have multiple shapes. The shape option allows a more fine-grained control over the contact
reporting.

.. note::
The expression in the list can contain the environment namespace regex ``{ENV_REGEX_NS}`` which
will be replaced with the environment namespace.
"""

filter_prim_paths_expr: list[str] | None = None
"""A list of expressions to filter contacts bodies with. Defaults to None. If both :attr:`contact_partners_body_expr` and
:attr:`contact_partners_shape_expr` are None, the contact with all bodies/shapes is reported.

Only one of :attr:`contact_partners_body_expr` or :attr:`contact_partners_shape_expr` can be provided.
If both are provided, an error will be raised.
"""List of body prim path expressions to filter contacts against. Defaults to None,
meaning contacts with all bodies are aggregated into the net force.

The contact sensor allows reporting contacts between the primitive specified with either :attr:`body_names_expr` or
:attr:`shape_names_expr` and other primitives in the scene. For instance, in a scene containing a robot, a ground
plane and an object, you can obtain individual contact reports of the base of the robot with the ground plane and
the object.
If provided, a per-partner force matrix (:attr:`ContactSensorData.force_matrix_w`) is
reported in addition to the net force. Each expression is matched against body prim paths
in the scene.

We make an explicit difference between a body and a shape. A body is a rigid body, while a shape is a collision
shape. A body can have multiple shapes. The shape option allows a more fine-grained control over the contact
reporting.
For shape-level filtering, see ``NewtonContactSensorCfg`` in ``isaaclab_newton``.

.. note::
The expression in the list can contain the environment namespace regex ``{ENV_REGEX_NS}`` which
will be replaced with the environment namespace.
Expressions can contain the environment namespace regex ``{ENV_REGEX_NS}``, which
is replaced with the environment namespace.

Example: ``{ENV_REGEX_NS}/Object`` will be replaced with ``/World/envs/env_.*/Object``.
Example: ``{ENV_REGEX_NS}/Object`` becomes ``/World/envs/env_.*/Object``.

.. attention::
The reporting of filtered contacts only works when the sensor primitive :attr:`prim_path` corresponds to a
single primitive in that environment. If the sensor primitive corresponds to multiple primitives, the
filtering will not work as expected. Please check :class:`~isaaclab.sensors.contact_sensor.ContactSensor`
for more details.
"""

filter_shape_paths_expr: list[str] | None = None
"""A list of expressions to filter contacts shapes with. Defaults to None. If both :attr:`contact_partners_body_expr` and
:attr:`contact_partners_shape_expr` are None, the contact with all bodies/shapes is reported.

Only one of :attr:`contact_partners_body_expr` or :attr:`contact_partners_shape_expr` can be provided.
If both are provided, an error will be raised.

The contact sensor allows reporting contacts between the primitive specified with either :attr:`body_names_expr` or
:attr:`shape_names_expr` and other primitives in the scene. For instance, in a scene containing a robot, a ground
plane and an object, you can obtain individual contact reports of the base of the robot with the ground plane and
the object.


We make an explicit difference between a body and a shape. A body is a rigid body, while a shape is a collision
shape. A body can have multiple shapes. The shape option allows a more fine-grained control over the contact
reporting.

.. note::
The expression in the list can contain the environment namespace regex ``{ENV_REGEX_NS}`` which
will be replaced with the environment namespace.

Example: ``{ENV_REGEX_NS}/Object`` will be replaced with ``/World/envs/env_.*/Object``.
Filtered contact reporting only works when :attr:`SensorBaseCfg.prim_path` matches a
single primitive per environment. For many-to-many filtering, see
``NewtonContactSensorCfg`` in ``isaaclab_newton``.
"""

visualizer_cfg: VisualizationMarkersCfg = CONTACT_SENSOR_MARKER_CFG.replace(prim_path="/Visuals/ContactSensor")
Expand Down
11 changes: 11 additions & 0 deletions source/isaaclab/isaaclab/sensors/frame_transformer/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,17 @@

"""Sub-module for frame transformer sensor."""

from .base_frame_transformer import BaseFrameTransformer
from .base_frame_transformer_data import BaseFrameTransformerData
from .frame_transformer import FrameTransformer
from .frame_transformer_cfg import FrameTransformerCfg, OffsetCfg
from .frame_transformer_data import FrameTransformerData

__all__ = [
"BaseFrameTransformer",
"BaseFrameTransformerData",
"FrameTransformer",
"FrameTransformerData",
"FrameTransformerCfg",
"OffsetCfg",
]
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
# 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

from __future__ import annotations

from abc import abstractmethod
from collections.abc import Sequence
from typing import TYPE_CHECKING

import warp as wp

from ..sensor_base import SensorBase

if TYPE_CHECKING:
from .base_frame_transformer_data import BaseFrameTransformerData
from .frame_transformer_cfg import FrameTransformerCfg


class BaseFrameTransformer(SensorBase):
"""Sensor reporting transforms of target frames relative to a source frame.

Source frame is set via :attr:`FrameTransformerCfg.prim_path`; target frames via
:attr:`FrameTransformerCfg.target_frames`. Both must be rigid bodies. Relative
transforms are derived from world-frame poses obtained from the physics engine.

Optional offsets on source and target frames allow measuring from points other
than the body origin (e.g. a tool-tip offset from the body center of mass).
"""

cfg: FrameTransformerCfg
"""The configuration parameters."""

def __init__(self, cfg: FrameTransformerCfg):
"""Initializes the frame transformer object.

Args:
cfg: The configuration parameters.
"""
# initialize base class
super().__init__(cfg)

def __str__(self) -> str:
"""Returns: A string containing information about the instance."""
return (
f"FrameTransformer @ '{self.cfg.prim_path}': \n"
f"\tupdate period (s) : {self.cfg.update_period}\n"
f"\tnumber of bodies : {self.num_bodies}\n"
f"\tbody names : {self.body_names}\n"
)

"""
Properties
"""

@property
@abstractmethod
def data(self) -> BaseFrameTransformerData:
"""Data from the sensor."""
raise NotImplementedError

@property
def num_bodies(self) -> int:
"""Number of target bodies tracked."""
return len(self._target_frame_body_names)

@property
def body_names(self) -> list[str]:
"""Ordered names of target bodies tracked."""
return self._target_frame_body_names

"""
Operations
"""

def reset(self, env_ids: Sequence[int] | None = None, env_mask: wp.array | None = None):
# reset the timers and counters
super().reset(env_ids, env_mask)

@abstractmethod
def find_bodies(self, name_keys: str | Sequence[str], preserve_order: bool = False) -> tuple[list[int], list[str]]:
"""Find target bodies by name.

Args:
name_keys: Regex or list of regexes to match target body names.
preserve_order: Whether to preserve the order of the name keys. Defaults to False.

Returns:
Tuple of (indices, names) for matched bodies.
"""
raise NotImplementedError

"""
Implementation.
"""

@abstractmethod
def _initialize_impl(self):
super()._initialize_impl()

@abstractmethod
def _update_buffers_impl(self, env_mask: wp.array | None):
"""Fills the buffers of the sensor data.

Args:
env_mask: Mask of the environments to update. None: update all environments.
"""
raise NotImplementedError

"""
Internal simulation callbacks.
"""

def _invalidate_initialize_callback(self, event):
"""Invalidates the scene elements."""
super()._invalidate_initialize_callback(event)
Loading
Loading