IsaacLab icon indicating copy to clipboard operation
IsaacLab copied to clipboard

Adds Raycaster with tracking for Dynamic Meshes

Open renezurbruegg opened this issue 4 months ago • 26 comments

Description

This PR introduces MultiMeshRayCaster and MultiMeshRayCasterCamera, an extension of the default RayCaster with the following enhancements:

  1. Raycasting against multiple target types : Supports primitive shapes (spheres, cubes, …) as well as arbitrary meshes.
  2. Dynamic mesh tracking : Keeps track of specified meshes, enabling raycasting against moving parts (e.g., robot links, articulated bodies, or dynamic obstacles).
  3. Memory-efficient caching : Avoids redundant memory usage by caching and reusing duplicate meshes.

This is joint work with @pascal-roth and @Mayankm96.

The default RayCaster was limited to static environments and required manual handling of moving meshes, which restricted its use for robotics scenarios where robots or obstacles move dynamically.

MultiMeshRayCaster addresses these limitations by and now supports raycasting against robot parts and other moving entities.


Usage

For a quick demo, run:

python scripts/demos/sensors/multi_mesh_raycaster.py --num_envs 16 --asset_type <allegro_hand|anymal_d|multi>
demo image

Drop-in replacement

Example change to migrate from RayCasterCfg to MultiMeshRayCasterCfg:

- ray_caster_cfg = RayCasterCfg(
+ ray_caster_cfg = MultiMeshRayCasterCfg(
      prim_path="{ENV_REGEX_NS}/Robot",
      mesh_prim_paths=[
         "/World/Ground",
+         MultiMeshRayCasterCfg.RaycastTargetCfg(target_prim_expr="{ENV_REGEX_NS}/Robot/LF_.*/visuals"),
+         MultiMeshRayCasterCfg.RaycastTargetCfg(target_prim_expr="{ENV_REGEX_NS}/Robot/RF_.*/visuals"),
+         MultiMeshRayCasterCfg.RaycastTargetCfg(target_prim_expr="{ENV_REGEX_NS}/Robot/LH_.*/visuals"),
+         MultiMeshRayCasterCfg.RaycastTargetCfg(target_prim_expr="{ENV_REGEX_NS}/Robot/RH_.*/visuals"),
+         MultiMeshRayCasterCfg.RaycastTargetCfg(target_prim_expr="{ENV_REGEX_NS}/Robot/base/visuals"),
      ],
      pattern_cfg=patterns.GridPatternCfg(resolution=resolution, size=(5.0, 5.0)),
 )

Benchmarking & Validation

To benchmark the new raycaster, run:

python scripts/benchmarks/benchmark_ray_caster.py

Then plot the results with:

python scripts/benchmarks/plot_raycast_results.py

This will generate outputs under: outputs/benchmarks/raycast_benchmark...

Example plots

big image
left image right image
bottom image

Type of Change

  • [x] New feature (non-breaking change which adds functionality)
  • [ ] This change requires a documentation update

Checklist

  • [x] I have run the pre-commit checks with ./isaaclab.sh --format
  • [ ] I have made corresponding changes to the documentation
  • [ ] My changes generate no new warnings
  • [x] I have added tests that prove my fix is effective or that my feature works
  • [ ] I have updated the changelog and the corresponding version in the extension's config/extension.toml file
  • [x] I have added my name to the CONTRIBUTORS.md or my name already exists there

renezurbruegg avatar Aug 28 '25 08:08 renezurbruegg

It looks very good on first pass thank you @pascal-roth @renezurbruegg @Mayankm96 , but I want to spend a bit more time review this carefully a bit later!

ooctipus avatar Sep 04 '25 21:09 ooctipus

Thanks a lot for the fast feedback! I believe I should have addressed all the comments that have been raised so far

renezurbruegg avatar Sep 05 '25 21:09 renezurbruegg

test_multi_mesh_ray_caster_camera.py tests are failing in CI. could you also run ./isaaclab.sh -f when the changes are ready pls?

kellyguo11 avatar Sep 07 '25 06:09 kellyguo11

hmm looks like there's still a failure in CI :(

| /workspace/isaaclab/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py  | FAILED |    30.52 |  12/21  |

kellyguo11 avatar Sep 09 '25 03:09 kellyguo11

hmm looks like there's still a failure in CI :(

| /workspace/isaaclab/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py  | FAILED |    30.52 |  12/21  |

@pascal-roth could you maybe quickly have a look?

renezurbruegg avatar Sep 09 '25 06:09 renezurbruegg

when the root prim of the sensor is an Xform prim, then we get into a huge slowdown due to IsaacSim (thanks @ooctipus for fining this issue). It will make sense to replicate the code we use for targets also for the root prim and resolve until we find a physics prim @renezurbruegg

pascal-roth avatar Sep 16 '25 09:09 pascal-roth

as an example

some robot has prim_path of {ENV_REGEX_NS}/Robot where the ArticulationRootAPI is applied other robot may have ArticulationRootAPI applied at prim_path {ENV_REGEX_NS}/Robot/root_joint

if user mistakenly place the raycasterCfg's prim path to the one that doesn't have ArticulationRootAPI, you will see the slow down.

ooctipus avatar Sep 16 '25 11:09 ooctipus

@pascal-roth if you find some time, maybe you can update the MultiMeshRayCasterCamera to also use to _update_rays_impl workflow, which updates the ray directions and sensor origin

renezurbruegg avatar Sep 16 '25 13:09 renezurbruegg

def create_primitive_mesh(prim) -> trimesh.Trimesh:
    prim_type = prim.GetTypeName()
    if prim_type == "Cube":
        size = UsdGeom.Cube(prim).GetSizeAttr().Get()
        return trimesh.creation.box(extents=(size, size, size))
    elif prim_type == "Sphere":
        r = UsdGeom.Sphere(prim).GetRadiusAttr().Get()
        return trimesh.creation.icosphere(subdivisions=3, radius=r)
    elif prim_type == "Cylinder":
        c = UsdGeom.Cylinder(prim)
        return trimesh.creation.cylinder(radius=c.GetRadiusAttr().Get(), height=c.GetHeightAttr().Get())
    elif prim_type == "Capsule":
        c = UsdGeom.Capsule(prim)
        tri_mesh = trimesh.creation.capsule(radius=c.GetRadiusAttr().Get(), height=c.GetHeightAttr().Get())
        if c.GetAxisAttr().Get() == "X":
            # rotate −90° about Y to point the length along +X
            R = rotation_matrix(np.radians(-90), [0, 1, 0])
            tri_mesh.apply_transform(R)
        elif c.GetAxisAttr().Get() == "Y":
            # rotate +90° about X to point the length along +Y
            R = rotation_matrix(np.radians(90), [1, 0, 0])
            tri_mesh.apply_transform(R)
        return tri_mesh

    elif prim_type == "Cone":
        c = UsdGeom.Cone(prim)
        radius = c.GetRadiusAttr().Get()
        height = c.GetHeightAttr().Get()
        mesh = trimesh.creation.cone(radius=radius, height=height)
        # shift all vertices down by height/2 for usd / trimesh cone primitive definiton discrepancy
        mesh.apply_translation((0.0, 0.0, -height / 2.0))
        return mesh
    else:
        raise KeyError(f"{prim_type} is not a valid primitive mesh type")

@renezurbruegg @pascal-roth I also have something in my other code to do primitive to trimesh conversion, I see currently only Plane, Cube, Sphere for ray-caster, could you please add the Cone, Capsule, Cylinder as well? Be careful with the descrepancy how trimesh cone and capsule convention might be a bit different from that of USD. I have written out the convention conversion in the code snippet above and tested it worked

if you find this single function nice, I'd also just replace all collapse helpfer functions and constant to just single function.

in my dexsuite environments, this code is also used, https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py

once you guys are done here, I will refactor my dexsuite environment to use your guys utility : )))

ooctipus avatar Sep 16 '25 13:09 ooctipus

I also see that I have a same triangulate face utility https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py

def _triangulate_faces(prim) -> np.ndarray:
    mesh = UsdGeom.Mesh(prim)
    counts = mesh.GetFaceVertexCountsAttr().Get()
    indices = mesh.GetFaceVertexIndicesAttr().Get()
    faces = []
    it = iter(indices)
    for cnt in counts:
        poly = [next(it) for _ in range(cnt)]
        for k in range(1, cnt - 1):
            faces.append([poly[0], poly[k], poly[k + 1]])
    return np.asarray(faces, dtype=np.int64)

your:

def convert_faces_to_triangles(faces: np.ndarray, point_counts: np.ndarray) -> np.ndarray:
    # check if the mesh is already triangulated
    if (point_counts == 3).all():
        return faces.reshape(-1, 3)  # already triangulated
    all_faces = []

    vertex_counter = 0
    # Iterates over all triangles of the mesh.
    # could be very slow for large meshes
    for num_points in point_counts:
        if num_points == 3:
            # triangle
            all_faces.append(faces[vertex_counter : vertex_counter + 3])
        elif num_points == 4:
            # quads. Subdivide into two triangles
            f = faces[vertex_counter : vertex_counter + 4]
            first_triangle = f[:3]
            second_triangle = np.array([f[0], f[2], f[3]])
            all_faces.append(first_triangle)
            all_faces.append(second_triangle)
        else:
            raise RuntimeError(f"Invalid number of points per face: {num_points}")

        vertex_counter += num_points
    return np.asarray(all_faces)

I wonder maybe you want the code still to work beyond num_points > 4?

ooctipus avatar Sep 16 '25 14:09 ooctipus

Thanks for this feature! I've noticed that the duplicate mesh detection in MultiMeshRayCaster._initialize_warp_meshes() (from multi_mesh_ray_caster.py) doesn't scale well with the number of meshes.

Currently, _registered_points_idx() iterates over all registered meshes and compares their vertices. This operation is roughly O(n * V) for each new mesh (n = number of registered meshes, V = vertex count), leading to an overall O(n² * V) cost during initialization as the list of registered meshes grows (loaded_vertices).

A more efficient alternative could be to use a hash-based lookup table to detect mesh duplicates. We can assign a hash key to each mesh based on its vertices and use it for fast duplicate checks. This would reduce the overall complexity to O(n * V) for the entire duplicate mesh detection process.

Example implementation:

def _get_mesh_key(vertices: np.ndarray) -> tuple[int, int, bytes]:
    """Build a key from the shape and data hash of a mesh vertex array."""
    data = np.ascontiguousarray(vertices).view(np.uint8)  # Ensure array is contiguous
    h = hashlib.blake2b(data, digest_size=16)
    return (vertices.shape[0], vertices.shape[1], h.digest())

And in _initialize_warp_meshes():

def _initialize_warp_meshes(self):
    ...
    for target_cfg in self._raycast_targets_cfg:
        ...
        registered_meshes: dict[tuple[int, int, bytes], int] = {}  # Maps mesh keys to wp_mesh indices 
        wp_mesh_ids = []

        for target_prim in target_prims:
        	...
            if str(target_prim.GetPath()) in MultiMeshRayCaster.meshes:
                wp_mesh_ids.append(MultiMeshRayCaster.meshes[str(target_prim.GetPath())].id)
                continue
            ...
            mesh_key = _get_mesh_key(trimesh_mesh.vertices)
            registered_idx = registered_meshes.get(mesh_key, -1)
            if registered_idx != -1 and self.cfg.reference_meshes:
                omni.log.info("Found a duplicate mesh, only reference the mesh.")
                wp_mesh_ids.append(wp_mesh_ids[registered_idx])
            else:
                wp_mesh = convert_to_warp_mesh(trimesh_mesh.vertices, trimesh_mesh.faces, device=self.device)
                MultiMeshRayCaster.meshes[str(target_prim.GetPath())] = wp_mesh
                wp_mesh_ids.append(wp_mesh.id)
                registered_meshes[mesh_key] = len(wp_mesh_ids) - 1  # Store wp_mesh idx

This approach should reduce initialization time significantly when processing multiple meshes (from O(n² * V) to O(n * V)).

pavelacamposp avatar Oct 07 '25 01:10 pavelacamposp

Thanks a lot for the valuable feedback. Hashing the vertices is a great idea to speed up retrieval. I’ll incorporate this, along with an additional check for potential hash collisions, once I find the time.

Also, note that cache lookups can be further accelerated by setting the is_shared flag in the configuration to true. This assumes that all environments share the same meshes, avoiding redundant checking for each one.

renezurbruegg avatar Oct 07 '25 01:10 renezurbruegg

This is definitely useful feedback @pavelacamposp

@renezurbruegg I suggest though that we keep this MR to the current limitation and make a separate one with the hashing implementation. Just to not have this MR hanging around for too long :)

Mayankm96 avatar Oct 07 '25 13:10 Mayankm96

def create_primitive_mesh(prim) -> trimesh.Trimesh:
    prim_type = prim.GetTypeName()
    if prim_type == "Cube":
        size = UsdGeom.Cube(prim).GetSizeAttr().Get()
        return trimesh.creation.box(extents=(size, size, size))
    elif prim_type == "Sphere":
        r = UsdGeom.Sphere(prim).GetRadiusAttr().Get()
        return trimesh.creation.icosphere(subdivisions=3, radius=r)
    elif prim_type == "Cylinder":
        c = UsdGeom.Cylinder(prim)
        return trimesh.creation.cylinder(radius=c.GetRadiusAttr().Get(), height=c.GetHeightAttr().Get())
    elif prim_type == "Capsule":
        c = UsdGeom.Capsule(prim)
        tri_mesh = trimesh.creation.capsule(radius=c.GetRadiusAttr().Get(), height=c.GetHeightAttr().Get())
        if c.GetAxisAttr().Get() == "X":
            # rotate −90° about Y to point the length along +X
            R = rotation_matrix(np.radians(-90), [0, 1, 0])
            tri_mesh.apply_transform(R)
        elif c.GetAxisAttr().Get() == "Y":
            # rotate +90° about X to point the length along +Y
            R = rotation_matrix(np.radians(90), [1, 0, 0])
            tri_mesh.apply_transform(R)
        return tri_mesh

    elif prim_type == "Cone":
        c = UsdGeom.Cone(prim)
        radius = c.GetRadiusAttr().Get()
        height = c.GetHeightAttr().Get()
        mesh = trimesh.creation.cone(radius=radius, height=height)
        # shift all vertices down by height/2 for usd / trimesh cone primitive definiton discrepancy
        mesh.apply_translation((0.0, 0.0, -height / 2.0))
        return mesh
    else:
        raise KeyError(f"{prim_type} is not a valid primitive mesh type")

@renezurbruegg @pascal-roth I also have something in my other code to do primitive to trimesh conversion, I see currently only Plane, Cube, Sphere for ray-caster, could you please add the Cone, Capsule, Cylinder as well? Be careful with the descrepancy how trimesh cone and capsule convention might be a bit different from that of USD. I have written out the convention conversion in the code snippet above and tested it worked

if you find this single function nice, I'd also just replace all collapse helpfer functions and constant to just single function.

in my dexsuite environments, this code is also used, https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py

once you guys are done here, I will refactor my dexsuite environment to use your guys utility : )))

Thanks a lot for the input. I added all prim types now and verified that they work correctly: image

renezurbruegg avatar Oct 10 '25 06:10 renezurbruegg

I also see that I have a same triangulate face utility https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py

def _triangulate_faces(prim) -> np.ndarray:
    mesh = UsdGeom.Mesh(prim)
    counts = mesh.GetFaceVertexCountsAttr().Get()
    indices = mesh.GetFaceVertexIndicesAttr().Get()
    faces = []
    it = iter(indices)
    for cnt in counts:
        poly = [next(it) for _ in range(cnt)]
        for k in range(1, cnt - 1):
            faces.append([poly[0], poly[k], poly[k + 1]])
    return np.asarray(faces, dtype=np.int64)

your:

def convert_faces_to_triangles(faces: np.ndarray, point_counts: np.ndarray) -> np.ndarray:
    # check if the mesh is already triangulated
    if (point_counts == 3).all():
        return faces.reshape(-1, 3)  # already triangulated
    all_faces = []

    vertex_counter = 0
    # Iterates over all triangles of the mesh.
    # could be very slow for large meshes
    for num_points in point_counts:
        if num_points == 3:
            # triangle
            all_faces.append(faces[vertex_counter : vertex_counter + 3])
        elif num_points == 4:
            # quads. Subdivide into two triangles
            f = faces[vertex_counter : vertex_counter + 4]
            first_triangle = f[:3]
            second_triangle = np.array([f[0], f[2], f[3]])
            all_faces.append(first_triangle)
            all_faces.append(second_triangle)
        else:
            raise RuntimeError(f"Invalid number of points per face: {num_points}")

        vertex_counter += num_points
    return np.asarray(all_faces)

I wonder maybe you want the code still to work beyond num_points > 4?

Thanks, Updated it with your generic fan triangulation

renezurbruegg avatar Oct 10 '25 07:10 renezurbruegg

@renezurbruegg @pascal-roth Should we review this again and then prepare it for merge?

Mayankm96 avatar Oct 14 '25 08:10 Mayankm96

@renezurbruegg @pascal-roth Should we review this again and then prepare it for merge?

Yes :+1:

There is one remaining comment from @ooctipus, which ideally would be resolved in this pr https://github.com/isaac-sim/IsaacLab/pull/3371

renezurbruegg avatar Oct 14 '25 12:10 renezurbruegg

@renezurbruegg we should probably do a quick profiling with tools like Nsight Systems or with Warp's ScopedTimer (https://nvidia.github.io/warp/profiling.html) to know our bottleneck for large resolutions, then we can also think about improving our kernel (maybe also for a next version)

pascal-roth avatar Oct 15 '25 15:10 pascal-roth

line 166 in source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera.py

if not target_cfg.is_global:

But I don't see is_global defined in target_cfg?

it should be changed to

target_cfg.track_mesh_transforms

am I right?

ooctipus avatar Oct 20 '25 06:10 ooctipus

@greptileai

Mayankm96 avatar Oct 22 '25 06:10 Mayankm96

I believe I addressed all relevant comments!

FYI: While cleaning up some warp kernels, I found a bug in the warp operators for atomic_min https://github.com/NVIDIA/warp/issues/1058. I believe this bug is quite severe and will hopefully be addressed soon. For now I added a fixme to the warp kernel sections.

renezurbruegg avatar Oct 26 '25 12:10 renezurbruegg

Bad Bot ;) The change should be fine. Each raycaster needs to lead the reference in "_initialize_warp_meshes". The caching and referencing happens properly in L198

renezurbruegg avatar Oct 26 '25 14:10 renezurbruegg

@renezurbruegg @pascal-roth @Mayankm96 - could we try to get another approval for this PR?

also looks like the doc building job is failing - https://github.com/isaac-sim/IsaacLab/actions/runs/19120760997/job/54640579518?pr=3298

kellyguo11 avatar Nov 07 '25 18:11 kellyguo11

Greptile Overview

Greptile Summary

This PR adds MultiMeshRayCaster and MultiMeshRayCasterCamera, extending the existing raycaster to support dynamic mesh tracking, multiple target types, and memory-efficient mesh caching.

Key Changes:

  • New MultiMeshRayCaster class enabling raycasting against moving meshes (robot links, articulated bodies) with per-environment tracking
  • Warp kernel infrastructure (raycast_static_meshes_kernel, raycast_dynamic_meshes_kernel) for GPU-accelerated raycasting with atomic operations to handle multiple meshes per ray
  • Mesh deduplication system comparing vertex arrays to avoid redundant GPU memory usage across environments
  • Camera variant (MultiMeshRayCasterCamera) generating depth images with proper coordinate frame transformations
  • New isaaclab.utils.mesh module converting USD primitives (spheres, cubes, cylinders, etc.) to trimesh objects
  • Comprehensive test coverage (1114 new test lines) validating multi-mesh scenarios, dynamic transforms, and mesh ID tracking

Technical Implementation:

  • Class-level mesh dictionaries (meshes, mesh_offsets, mesh_views) shared across instances for memory efficiency
  • Per-environment mesh ID arrays (mesh_ids_wp) enabling batched raycasting across multiple environments
  • Optional transform tracking via track_mesh_transforms flag - static meshes skip pose updates for performance
  • Mesh merging capability combining multiple child meshes into single raycasting target

Issues Found:

  • Minor: Empty mesh prim handling at line 206 uses continue which could leave _num_meshes_per_env incomplete, potentially causing KeyError in later processing
  • Most previously reported issues are either false positives or acknowledged design choices (e.g., Warp atomic_min race condition is documented upstream issue)

Confidence Score: 4/5

  • Safe to merge with one minor logic issue noted that should be reviewed but likely doesn't affect typical usage scenarios
  • The implementation is well-architected with comprehensive test coverage (1114 new test lines), proper GPU memory management through mesh deduplication, and clean separation of concerns. The warp kernel race condition is a known upstream issue documented in the code. The one issue identified (incomplete _num_meshes_per_env handling when mesh prims are empty) is edge-case behavior that likely won't affect normal operation but should be validated. The PR successfully achieves its goal of enabling dynamic mesh raycasting while maintaining backward compatibility.
  • source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster.py - validate empty mesh prim handling around line 206-215 doesn't cause downstream KeyErrors

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster.py 4/5 Core implementation of multi-mesh raycasting with dynamic tracking, mesh deduplication, and per-environment mesh management. Minor issues with early-return logic and mesh counting.
source/isaaclab/isaaclab/utils/warp/kernels.py 4/5 New warp kernels for static and dynamic mesh raycasting. Race condition is documented as known issue with Warp library. Docstring shape mismatches noted in previous reviews.
source/isaaclab/isaaclab/utils/warp/ops.py 4/5 Added raycast_single_mesh and raycast_dynamic_meshes functions with proper tensor management. Quaternion conversion and initialization patterns are correct.
source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera.py 4/5 Camera implementation with image-based raycasting output. Properly handles depth clipping and coordinate frame transformations. Multiple inheritance from RayCasterCamera and MultiMeshRayCaster works as expected.
source/isaaclab/isaaclab/utils/mesh.py 5/5 New utility module for converting USD geometric primitives to trimesh objects. Clean implementation with proper axis handling for cylinders and capsules.
source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py 4/5 Modified base RayCaster class to support mesh tracking infrastructure. Added class-level mesh dictionaries and tracking logic.

Sequence Diagram

sequenceDiagram
    participant User
    participant MultiMeshRayCaster
    participant MultiMeshRayCasterCamera
    participant WarpOps
    participant WarpKernels
    participant MeshUtils
    
    Note over User,MeshUtils: Initialization Phase
    User->>MultiMeshRayCaster: __init__(cfg)
    MultiMeshRayCaster->>MultiMeshRayCaster: _initialize_warp_meshes()
    MultiMeshRayCaster->>MeshUtils: find_matching_prims(target_prim_expr)
    MeshUtils-->>MultiMeshRayCaster: target_prims[]
    
    loop For each target prim
        MultiMeshRayCaster->>MeshUtils: get_all_matching_child_prims()
        MeshUtils-->>MultiMeshRayCaster: mesh_prims[]
        MultiMeshRayCaster->>MeshUtils: create_trimesh_from_geom_*()
        MeshUtils-->>MultiMeshRayCaster: trimesh_mesh
        MultiMeshRayCaster->>MultiMeshRayCaster: Check for duplicate vertices
        alt Duplicate found and reference_meshes=True
            MultiMeshRayCaster->>MultiMeshRayCaster: Reuse existing wp_mesh.id
        else New mesh
            MultiMeshRayCaster->>WarpOps: convert_to_warp_mesh()
            WarpOps-->>MultiMeshRayCaster: wp_mesh
        end
        MultiMeshRayCaster->>MultiMeshRayCaster: Store in class-level meshes dict
    end
    
    MultiMeshRayCaster->>MultiMeshRayCaster: Create mesh_ids_wp array (num_envs x num_meshes)
    alt track_mesh_transforms=True
        MultiMeshRayCaster->>MultiMeshRayCaster: _get_trackable_prim_view()
        MultiMeshRayCaster->>MultiMeshRayCaster: Store in mesh_views dict
    end
    
    Note over User,WarpKernels: Update/Raycast Phase
    User->>MultiMeshRayCaster: data (property access)
    MultiMeshRayCaster->>MultiMeshRayCaster: _update_outdated_buffers()
    MultiMeshRayCaster->>MultiMeshRayCaster: _update_buffers_impl(env_ids)
    
    alt track_mesh_transforms=True
        loop For each tracked mesh view
            MultiMeshRayCaster->>MultiMeshRayCaster: obtain_world_pose_from_view()
            MultiMeshRayCaster->>MultiMeshRayCaster: Apply mesh_offsets
            MultiMeshRayCaster->>MultiMeshRayCaster: Update _mesh_positions_w, _mesh_orientations_w
        end
    end
    
    MultiMeshRayCaster->>WarpOps: raycast_dynamic_meshes()
    WarpOps->>WarpOps: Initialize output tensors
    WarpOps->>WarpOps: Convert quaternions wxyz->xyzw
    
    alt Static meshes (no transforms)
        WarpOps->>WarpKernels: raycast_static_meshes_kernel()
    else Dynamic meshes (with transforms)
        WarpOps->>WarpKernels: raycast_dynamic_meshes_kernel()
    end
    
    WarpKernels->>WarpKernels: Thread per (mesh_id, env, ray)
    loop For each mesh
        WarpKernels->>WarpKernels: Transform ray to mesh local space
        WarpKernels->>WarpKernels: wp.mesh_query_ray()
        alt Hit found and closer than current
            WarpKernels->>WarpKernels: atomic_min(ray_distance)
            WarpKernels->>WarpKernels: Update ray_hits, ray_normal, ray_face_id, ray_mesh_id
        end
    end
    
    WarpKernels-->>WarpOps: Hit results
    WarpOps-->>MultiMeshRayCaster: ray_hits_w, mesh_ids
    MultiMeshRayCaster->>MultiMeshRayCaster: Store in _data container
    MultiMeshRayCaster-->>User: MultiMeshRayCasterData
    
    Note over User,WarpKernels: Camera-Specific Flow
    User->>MultiMeshRayCasterCamera: data (property access)
    MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: _update_buffers_impl()
    MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: Update mesh transforms (inherited)
    MultiMeshRayCasterCamera->>WarpOps: raycast_dynamic_meshes()
    WarpOps-->>MultiMeshRayCasterCamera: ray_hits, ray_depth, ray_normal, mesh_ids
    
    alt distance_to_image_plane requested
        MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: Transform to camera frame
        MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: Extract z-component
        MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: Apply depth clipping
    end
    
    MultiMeshRayCasterCamera->>MultiMeshRayCasterCamera: Reshape to image shape (H, W)
    MultiMeshRayCasterCamera-->>User: MultiMeshRayCasterCameraData

greptile-apps[bot] avatar Nov 11 '25 01:11 greptile-apps[bot]

Simulation startup becomes extremely slow when using the RayCaster sensor with large numbers of environments

Description

When running the RayCaster sensor branch in IsaacSim, the simulation initialization time increases drastically as the number of environments grows.

The program does not crash, but the simulation hangs for a long time at the message: [INFO]: Starting the simulation. This may take a few seconds. Please wait...


Steps to Reproduce

  1. Launch the simulation using the RayCaster sensor branch.
  2. Set the number of environments to a large value (e.g., 1000, 2000, or more).
  3. Observe the time it takes to start the simulation.

Observed Behavior

  • The console shows normal terrain and scene creation messages, then remains at picture

  • The program stays in this state for a long time without proceeding.

  • Startup time increases roughly linearly with the number of environments.

Number of Environments Approx. Startup Time
1 Immediate
1000 ~1 minute
4000 Several minutes

Expected Behavior

The simulation should start within a reasonable time regardless of the number of environments, consistent with other sensors or configurations.


Environment

  • IsaacSim version: [your version]
  • RayCaster branch: [branch name or commit hash]
  • GPU / OS: [your specs]
  • Number of environments tested: up to 4000
fe5b1e9eb50aa8db7d162d1476d9356e

XiaoYi-Wei avatar Nov 12 '25 10:11 XiaoYi-Wei

### Issue Description

I found a potential bug in the file:

`source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera.py`  
at **line 178**.

The current code is:

```python
self.ray_hits_w, ray_depth, ray_normal, _, ray_mesh_ids = raycast_dynamic_meshes()

However, the first returned value of raycast_dynamic_meshes() has the shape:

[len(env_ids), num_rays, 3]

This causes a CUDA kernel out-of-bounds access, because self.ray_hits_w expects indexing over all environments, while the returned tensor only corresponds to len(env_ids). The issue doesn't throw an error immediately because self.ray_hits_w is not used later in this path, but the kernel still performs invalid memory access.

Suggested Fix

It seems the assignment should correctly write only to the selected environments:

self.ray_hits_w[env_ids], ray_depth, ray_normal, _, ray_mesh_ids = raycast_dynamic_meshes()

This aligns the shapes and prevents hidden OOB kernel access.

XiaoYi-Wei avatar Nov 13 '25 07:11 XiaoYi-Wei

@XiaoYi-Wei thanks for the catch, should be fixed now

pascal-roth avatar Nov 18 '25 23:11 pascal-roth

need to merge #3924 first

pascal-roth avatar Nov 19 '25 22:11 pascal-roth